diff --git a/terrain_navigation_ros/include/terrain_navigation_ros/terrain_planner.h b/terrain_navigation_ros/include/terrain_navigation_ros/terrain_planner.h index aef83cc4..6e827179 100644 --- a/terrain_navigation_ros/include/terrain_navigation_ros/terrain_planner.h +++ b/terrain_navigation_ros/include/terrain_navigation_ros/terrain_planner.h @@ -165,7 +165,6 @@ class TerrainPlanner { ros::Publisher camera_pose_pub_; ros::Publisher posehistory_pub_; ros::Publisher referencehistory_pub_; - ros::Publisher position_setpoint_pub_; ros::Publisher global_position_setpoint_pub_; ros::Publisher position_target_pub_; ros::Publisher path_target_pub_; diff --git a/terrain_navigation_ros/src/terrain_planner.cpp b/terrain_navigation_ros/src/terrain_planner.cpp index db17cef6..bded5154 100644 --- a/terrain_navigation_ros/src/terrain_planner.cpp +++ b/terrain_navigation_ros/src/terrain_planner.cpp @@ -74,7 +74,6 @@ TerrainPlanner::TerrainPlanner(const ros::NodeHandle &nh, const ros::NodeHandle nh_.subscribe("mavros/state", 1, &TerrainPlanner::mavstateCallback, this, ros::TransportHints().tcpNoDelay()); mavmission_sub_ = nh_.subscribe("mavros/mission/waypoints", 1, &TerrainPlanner::mavMissionCallback, this, ros::TransportHints().tcpNoDelay()); - position_setpoint_pub_ = nh_.advertise("mavros/setpoint_raw/local", 1); global_position_setpoint_pub_ = nh_.advertise("mavros/setpoint_raw/global", 1); path_target_pub_ = nh_.advertise("mavros/trajectory/generated", 1); vehicle_pose_pub_ = nh_.advertise("vehicle_pose_marker", 1);