diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp index 9993d9190ae..d9e9ddb3c6e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp @@ -86,7 +86,6 @@ class FootprintSubscriber */ void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg); - std::string topic_name_; tf2_ros::Buffer & tf_; std::string robot_base_frame_; double transform_tolerance_; diff --git a/nav2_costmap_2d/src/footprint_subscriber.cpp b/nav2_costmap_2d/src/footprint_subscriber.cpp index 45e60db65e8..2c269fa3b06 100644 --- a/nav2_costmap_2d/src/footprint_subscriber.cpp +++ b/nav2_costmap_2d/src/footprint_subscriber.cpp @@ -31,8 +31,7 @@ FootprintSubscriber::FootprintSubscriber( tf2_ros::Buffer & tf, std::string robot_base_frame, double transform_tolerance) -: topic_name_(topic_name), - tf_(tf), +: tf_(tf), robot_base_frame_(robot_base_frame), transform_tolerance_(transform_tolerance) { @@ -48,8 +47,7 @@ FootprintSubscriber::FootprintSubscriber( tf2_ros::Buffer & tf, std::string robot_base_frame, double transform_tolerance) -: topic_name_(topic_name), - tf_(tf), +: tf_(tf), robot_base_frame_(robot_base_frame), transform_tolerance_(transform_tolerance) {