diff options
author | Andreas Antener <antener_a@gmx.ch> | 2015-04-07 00:13:12 +0200 |
---|---|---|
committer | Andreas Antener <antener_a@gmx.ch> | 2015-04-08 13:41:40 +0200 |
commit | 9924f5519f907568351aaa66fba01190b682a396 (patch) | |
tree | 5e5bef67e482a22e82eca22d74efde2992e2996d /src/platforms | |
parent | f8c8876642857520e85ec8ca027146c11b4301e3 (diff) | |
download | px4-firmware-9924f5519f907568351aaa66fba01190b682a396.tar.gz px4-firmware-9924f5519f907568351aaa66fba01190b682a396.tar.bz2 px4-firmware-9924f5519f907568351aaa66fba01190b682a396.zip |
update attitude and position setpoint topics
Diffstat (limited to 'src/platforms')
2 files changed, 3 insertions, 3 deletions
diff --git a/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp b/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp index fb0b09de1..328f545c6 100644 --- a/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp +++ b/src/platforms/ros/nodes/demo_offboard_attitude_setpoints/demo_offboard_attitude_setpoints.cpp @@ -49,8 +49,8 @@ DemoOffboardAttitudeSetpoints::DemoOffboardAttitudeSetpoints() : _n(), - _attitude_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint/attitude", 1)), - _thrust_sp_pub(_n.advertise<std_msgs::Float64>("mavros/setpoint/att_throttle", 1)) + _attitude_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_attitude/attitude", 1)), + _thrust_sp_pub(_n.advertise<std_msgs::Float64>("mavros/setpoint_attitude/att_throttle", 1)) { } diff --git a/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp b/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp index 125ceaddc..8a626f255 100644 --- a/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp +++ b/src/platforms/ros/nodes/demo_offboard_position_setpoints/demo_offboard_position_setpoints.cpp @@ -46,7 +46,7 @@ DemoOffboardPositionSetpoints::DemoOffboardPositionSetpoints() : _n(), - _local_position_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint/local_position", 1)) + _local_position_sp_pub(_n.advertise<geometry_msgs::PoseStamped>("mavros/setpoint_position/local", 1)) { } |