Skip to content

Commit

Permalink
fix tf_broadcaster in amcl_node
Browse files Browse the repository at this point in the history
Signed-off-by: zhenpeng ge <[email protected]>
  • Loading branch information
gezp committed May 27, 2022
1 parent e581eef commit 67eda7d
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1438,7 +1438,7 @@ AmclNode::initTransforms()
callback_group_);
tf_buffer_->setCreateTimerInterface(timer_interface);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this(), true);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());

sent_first_transform_ = false;
latest_tf_valid_ = false;
Expand Down

0 comments on commit 67eda7d

Please sign in to comment.