Skip to content

Commit

Permalink
reduce amcl_node nodes
Browse files Browse the repository at this point in the history
Signed-off-by: zhenpeng ge <zhenpeng.ge@qq.com>
  • Loading branch information
gezp committed Aug 11, 2021
1 parent 9759fd1 commit afcda28
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 9 deletions.
3 changes: 2 additions & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,8 @@ class AmclNode : public nav2_util::LifecycleNode
* @brief Initialize incoming data message subscribers and filters
*/
void initMessageFilters();
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
message_filters::Connection laser_scan_connection_;

Expand Down
19 changes: 11 additions & 8 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ namespace nav2_amcl
using nav2_util::geometry_utils::orientationAroundZAxis;

AmclNode::AmclNode()
: nav2_util::LifecycleNode("amcl", "", true)
: nav2_util::LifecycleNode("amcl", "")
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down Expand Up @@ -1219,13 +1219,13 @@ AmclNode::initTransforms()
RCLCPP_INFO(get_logger(), "initTransforms");

// Initialize transform listener and broadcaster
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(rclcpp_node_->get_clock());
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
rclcpp_node_->get_node_base_interface(),
rclcpp_node_->get_node_timers_interface());
get_node_base_interface(),
get_node_timers_interface());
tf_buffer_->setCreateTimerInterface(timer_interface);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(rclcpp_node_);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());

sent_first_transform_ = false;
latest_tf_valid_ = false;
Expand All @@ -1235,11 +1235,14 @@ AmclNode::initTransforms()
void
AmclNode::initMessageFilters()
{
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data);
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data);

laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_);
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
get_node_logging_interface(),
get_node_clock_interface());

laser_scan_connection_ = laser_scan_filter_->registerCallback(
std::bind(
Expand Down

0 comments on commit afcda28

Please sign in to comment.