Skip to content

Commit

Permalink
remove extra sub (#3025)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwallace42 authored Jun 19, 2022
1 parent b191b52 commit 08e558f
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down
6 changes: 2 additions & 4 deletions nav2_costmap_2d/src/footprint_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand All @@ -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)
{
Expand Down

0 comments on commit 08e558f

Please sign in to comment.