diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 86571e81f8e..0671c79d90a 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -225,7 +225,6 @@ AmclNode::AmclNode() AmclNode::~AmclNode() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml index 53ab496bebd..54773241bfb 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml @@ -69,6 +69,8 @@ bt_navigator: - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_transform_available_condition_bt_node diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml index a4a62d6b1a5..2c1658f1482 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml @@ -69,6 +69,8 @@ bt_navigator: - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_transform_available_condition_bt_node diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/ros_topic_logger.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/ros_topic_logger.hpp index c517d6c9e54..27fe61eebce 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/ros_topic_logger.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/ros_topic_logger.hpp @@ -27,7 +27,7 @@ namespace nav2_bt_navigator class RosTopicLogger : public BT::StatusChangeLogger { public: - RosTopicLogger(const rclcpp::Node::SharedPtr & ros_node, const BT::Tree & tree); + RosTopicLogger(const rclcpp::Node::WeakPtr & ros_node, const BT::Tree & tree); void callback( BT::Duration timestamp, @@ -38,7 +38,8 @@ class RosTopicLogger : public BT::StatusChangeLogger void flush() override; protected: - rclcpp::Node::SharedPtr ros_node_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("bt_navigator")}; rclcpp::Publisher::SharedPtr log_pub_; std::vector event_log_; }; diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 863d2635b3c..7bf86cf7e83 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -16,7 +16,6 @@ #include #include -#include #include #include #include @@ -52,7 +51,7 @@ BtNavigator::BtNavigator() "nav2_distance_controller_bt_node", "nav2_speed_controller_bt_node", "nav2_truncate_path_action_bt_node", - "nav2_change_goal_node_bt_node", + "nav2_goal_updater_node_bt_node", "nav2_recovery_node_bt_node", "nav2_pipeline_sequence_bt_node", "nav2_round_robin_node_bt_node", @@ -72,7 +71,6 @@ BtNavigator::BtNavigator() BtNavigator::~BtNavigator() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn @@ -252,7 +250,7 @@ BtNavigator::navigateToPose() auto bt_xml_filename = action_server_->get_current_goal()->behavior_tree; // Empty id in request is default for backward compatibility - bt_xml_filename = bt_xml_filename == "" ? default_bt_xml_filename_ : bt_xml_filename; + bt_xml_filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename; if (!loadBehaviorTree(bt_xml_filename)) { RCLCPP_ERROR( diff --git a/nav2_bt_navigator/src/ros_topic_logger.cpp b/nav2_bt_navigator/src/ros_topic_logger.cpp index 472b30d323b..5a11724db5d 100644 --- a/nav2_bt_navigator/src/ros_topic_logger.cpp +++ b/nav2_bt_navigator/src/ros_topic_logger.cpp @@ -21,10 +21,13 @@ namespace nav2_bt_navigator { RosTopicLogger::RosTopicLogger( - const rclcpp::Node::SharedPtr & ros_node, const BT::Tree & tree) -: StatusChangeLogger(tree.rootNode()), ros_node_(ros_node) + const rclcpp::Node::WeakPtr & ros_node, const BT::Tree & tree) +: StatusChangeLogger(tree.rootNode()) { - log_pub_ = ros_node_->create_publisher( + auto node = ros_node.lock(); + clock_ = node->get_clock(); + logger_ = node->get_logger(); + log_pub_ = node->create_publisher( "behavior_tree_log", rclcpp::QoS(10)); } @@ -51,7 +54,7 @@ void RosTopicLogger::callback( event_log_.push_back(std::move(event)); RCLCPP_DEBUG( - ros_node_->get_logger(), "[%.3f]: %25s %s -> %s", + logger_, "[%.3f]: %25s %s -> %s", std::chrono::duration(timestamp).count(), node.name().c_str(), toStr(prev_status, true).c_str(), @@ -60,9 +63,9 @@ void RosTopicLogger::callback( void RosTopicLogger::flush() { - if (event_log_.size() > 0) { + if (!event_log_.empty()) { auto log_msg = std::make_unique(); - log_msg->timestamp = ros_node_->now(); + log_msg->timestamp = clock_->now(); log_msg->event_log = event_log_; log_pub_->publish(std::move(log_msg)); event_log_.clear(); diff --git a/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp b/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp index b7e483c1611..f95b5f2f921 100644 --- a/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp @@ -58,7 +58,7 @@ class SimpleGoalChecker : public nav2_core::GoalChecker SimpleGoalChecker(); // Standard GoalChecker Interface void initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) override; void reset() override; bool isGoalReached( diff --git a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp index 92a5374a5e0..f4a2c6d25a0 100644 --- a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp @@ -34,7 +34,7 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker { public: void initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) override; bool check(geometry_msgs::msg::PoseStamped & current_pose) override; void reset() override; @@ -52,7 +52,7 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker */ void reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose); - rclcpp_lifecycle::LifecycleNode::SharedPtr nh_; + rclcpp::Clock::SharedPtr clock_; double radius_; rclcpp::Duration time_allowance_{0, 0}; diff --git a/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp b/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp index 869edb6330b..160ac60f091 100644 --- a/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp @@ -55,7 +55,7 @@ class StoppedGoalChecker : public SimpleGoalChecker StoppedGoalChecker(); // Standard GoalChecker Interface void initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) override; bool isGoalReached( const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose, diff --git a/nav2_controller/plugins/simple_goal_checker.cpp b/nav2_controller/plugins/simple_goal_checker.cpp index f1ec7dba6ca..983032ee660 100644 --- a/nav2_controller/plugins/simple_goal_checker.cpp +++ b/nav2_controller/plugins/simple_goal_checker.cpp @@ -56,22 +56,24 @@ SimpleGoalChecker::SimpleGoalChecker() } void SimpleGoalChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { + auto node = parent.lock(); + nav2_util::declare_parameter_if_not_declared( - nh, + node, plugin_name + ".xy_goal_tolerance", rclcpp::ParameterValue(0.25)); nav2_util::declare_parameter_if_not_declared( - nh, + node, plugin_name + ".yaw_goal_tolerance", rclcpp::ParameterValue(0.25)); nav2_util::declare_parameter_if_not_declared( - nh, + node, plugin_name + ".stateful", rclcpp::ParameterValue(true)); - nh->get_parameter(plugin_name + ".xy_goal_tolerance", xy_goal_tolerance_); - nh->get_parameter(plugin_name + ".yaw_goal_tolerance", yaw_goal_tolerance_); - nh->get_parameter(plugin_name + ".stateful", stateful_); + node->get_parameter(plugin_name + ".xy_goal_tolerance", xy_goal_tolerance_); + node->get_parameter(plugin_name + ".yaw_goal_tolerance", yaw_goal_tolerance_); + node->get_parameter(plugin_name + ".stateful", stateful_); xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_; } diff --git a/nav2_controller/plugins/simple_progress_checker.cpp b/nav2_controller/plugins/simple_progress_checker.cpp index 498d13256cb..542c8226efa 100644 --- a/nav2_controller/plugins/simple_progress_checker.cpp +++ b/nav2_controller/plugins/simple_progress_checker.cpp @@ -27,18 +27,21 @@ namespace nav2_controller static double pose_distance(const geometry_msgs::msg::Pose2D &, const geometry_msgs::msg::Pose2D &); void SimpleProgressChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { - nh_ = node; + auto node = parent.lock(); + + clock_ = node->get_clock(); + nav2_util::declare_parameter_if_not_declared( - nh_, plugin_name + ".required_movement_radius", rclcpp::ParameterValue(0.5)); + node, plugin_name + ".required_movement_radius", rclcpp::ParameterValue(0.5)); nav2_util::declare_parameter_if_not_declared( - nh_, plugin_name + ".movement_time_allowance", rclcpp::ParameterValue(10.0)); + node, plugin_name + ".movement_time_allowance", rclcpp::ParameterValue(10.0)); // Scale is set to 0 by default, so if it was not set otherwise, set to 0 - nh_->get_parameter_or(plugin_name + ".required_movement_radius", radius_, 0.5); + node->get_parameter_or(plugin_name + ".required_movement_radius", radius_, 0.5); double time_allowance_param = 0.0; - nh_->get_parameter_or(plugin_name + ".movement_time_allowance", time_allowance_param, 10.0); + node->get_parameter_or(plugin_name + ".movement_time_allowance", time_allowance_param, 10.0); time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param); } @@ -53,10 +56,7 @@ bool SimpleProgressChecker::check(geometry_msgs::msg::PoseStamped & current_pose reset_baseline_pose(current_pose2d); return true; } - if ((nh_->now() - baseline_time_) > time_allowance_) { - return false; - } - return true; + return !((clock_->now() - baseline_time_) > time_allowance_); } void SimpleProgressChecker::reset() @@ -67,17 +67,13 @@ void SimpleProgressChecker::reset() void SimpleProgressChecker::reset_baseline_pose(const geometry_msgs::msg::Pose2D & pose) { baseline_pose_ = pose; - baseline_time_ = nh_->now(); + baseline_time_ = clock_->now(); baseline_pose_set_ = true; } bool SimpleProgressChecker::is_robot_moved_enough(const geometry_msgs::msg::Pose2D & pose) { - if (pose_distance(pose, baseline_pose_) > radius_) { - return true; - } else { - return false; - } + return pose_distance(pose, baseline_pose_) > radius_; } static double pose_distance( diff --git a/nav2_controller/plugins/stopped_goal_checker.cpp b/nav2_controller/plugins/stopped_goal_checker.cpp index 2e24ad181aa..d6d409f1900 100644 --- a/nav2_controller/plugins/stopped_goal_checker.cpp +++ b/nav2_controller/plugins/stopped_goal_checker.cpp @@ -51,20 +51,22 @@ StoppedGoalChecker::StoppedGoalChecker() } void StoppedGoalChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { - SimpleGoalChecker::initialize(nh, plugin_name); + SimpleGoalChecker::initialize(parent, plugin_name); + + auto node = parent.lock(); nav2_util::declare_parameter_if_not_declared( - nh, + node, plugin_name + ".rot_stopped_velocity", rclcpp::ParameterValue(0.25)); nav2_util::declare_parameter_if_not_declared( - nh, + node, plugin_name + ".trans_stopped_velocity", rclcpp::ParameterValue(0.25)); - nh->get_parameter(plugin_name + ".rot_stopped_velocity", rot_stopped_velocity_); - nh->get_parameter(plugin_name + ".trans_stopped_velocity", trans_stopped_velocity_); + node->get_parameter(plugin_name + ".rot_stopped_velocity", rot_stopped_velocity_); + node->get_parameter(plugin_name + ".trans_stopped_velocity", trans_stopped_velocity_); } bool StoppedGoalChecker::isGoalReached( diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp index ed5e1d6c0c2..1765ac443e2 100644 --- a/nav2_controller/src/nav2_controller.cpp +++ b/nav2_controller/src/nav2_controller.cpp @@ -62,7 +62,9 @@ ControllerServer::ControllerServer() ControllerServer::~ControllerServer() { - RCLCPP_INFO(get_logger(), "Destroying"); + progress_checker_.reset(); + goal_checker_.reset(); + controllers_.clear(); } nav2_util::CallbackReturn @@ -72,7 +74,6 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) RCLCPP_INFO(get_logger(), "Configuring controller interface"); - get_parameter("progress_checker_plugin", progress_checker_id_); if (progress_checker_id_ == default_progress_checker_id_) { nav2_util::declare_parameter_if_not_declared( @@ -394,10 +395,7 @@ void ControllerServer::updateGlobalPath() void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity) { auto cmd_vel = std::make_unique(velocity.twist); - if ( - vel_publisher_->is_activated() && - this->count_subscribers(vel_publisher_->get_topic_name()) > 0) - { + if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) { vel_publisher_->publish(std::move(cmd_vel)); } } diff --git a/nav2_core/include/nav2_core/controller.hpp b/nav2_core/include/nav2_core/controller.hpp index 69aa10f25b0..e60c0288169 100644 --- a/nav2_core/include/nav2_core/controller.hpp +++ b/nav2_core/include/nav2_core/controller.hpp @@ -72,7 +72,7 @@ class Controller * @param costmap_ros A pointer to the costmap */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr &, + const rclcpp_lifecycle::LifecycleNode::WeakPtr &, std::string name, const std::shared_ptr &, const std::shared_ptr &) = 0; diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index 7245e6aedc0..dff1207b88f 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -48,7 +48,7 @@ class GlobalPlanner * @param costmap_ros A pointer to the costmap */ virtual void configure( - rclcpp_lifecycle::LifecycleNode::SharedPtr parent, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) = 0; diff --git a/nav2_core/include/nav2_core/goal_checker.hpp b/nav2_core/include/nav2_core/goal_checker.hpp index a8006e137a4..2cb331688b0 100644 --- a/nav2_core/include/nav2_core/goal_checker.hpp +++ b/nav2_core/include/nav2_core/goal_checker.hpp @@ -64,10 +64,10 @@ class GoalChecker /** * @brief Initialize any parameters from the NodeHandle - * @param nh NodeHandle for grabbing parameters + * @param parent Node pointer for grabbing parameters */ virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & nh, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) = 0; virtual void reset() = 0; /** diff --git a/nav2_core/include/nav2_core/progress_checker.hpp b/nav2_core/include/nav2_core/progress_checker.hpp index 2dd9c5bef89..0ab0402bf13 100644 --- a/nav2_core/include/nav2_core/progress_checker.hpp +++ b/nav2_core/include/nav2_core/progress_checker.hpp @@ -40,10 +40,10 @@ class ProgressChecker /** * @brief Initialize parameters for ProgressChecker - * @param node Node pointer + * @param parent Node pointer */ virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) = 0; /** * @brief Checks if the robot has moved compare to previous diff --git a/nav2_core/include/nav2_core/recovery.hpp b/nav2_core/include/nav2_core/recovery.hpp index 5d3fa6de52e..a800b2d21f5 100644 --- a/nav2_core/include/nav2_core/recovery.hpp +++ b/nav2_core/include/nav2_core/recovery.hpp @@ -47,7 +47,7 @@ class Recovery * @param costmap_ros A pointer to the costmap */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr parent, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf, std::shared_ptr collision_checker) = 0; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp index f1378848dfd..adee89f1771 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp @@ -34,7 +34,7 @@ class Costmap2DROS; class ClearCostmapService { public: - ClearCostmapService(nav2_util::LifecycleNode::SharedPtr node, Costmap2DROS & costmap); + ClearCostmapService(const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap); ClearCostmapService() = delete; @@ -48,8 +48,8 @@ class ClearCostmapService void clearEntirely(); private: - // The ROS node to use for getting parameters, creating the service and logging - nav2_util::LifecycleNode::SharedPtr node_; + // The Logger object for logging + rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")}; // The costmap to clear Costmap2DROS & costmap_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp index 83349d44704..ee276442ca4 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp @@ -67,7 +67,7 @@ class Costmap2DPublisher * @brief Constructor for the Costmap2DPublisher */ Costmap2DPublisher( - nav2_util::LifecycleNode::SharedPtr ros_node, + const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2D * costmap, std::string global_frame, std::string topic_name, @@ -130,7 +130,9 @@ class Costmap2DPublisher const std::shared_ptr request, const std::shared_ptr response); - nav2_util::LifecycleNode::SharedPtr node_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")}; + Costmap2D * costmap_; std::string global_frame_; std::string topic_name_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 541a246a513..1a3a7223b62 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -182,7 +182,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode LayeredCostmap * getLayeredCostmap() { - return layered_costmap_; + return layered_costmap_.get(); } /** @brief Returns the current padded footprint as a geometry_msgs::msg::Polygon. */ @@ -254,7 +254,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode // Publishers and subscribers rclcpp_lifecycle::LifecyclePublisher::SharedPtr footprint_pub_; - Costmap2DPublisher * costmap_publisher_{nullptr}; + std::unique_ptr costmap_publisher_{nullptr}; rclcpp::Subscription::SharedPtr footprint_sub_; rclcpp::Subscription::SharedPtr parameter_sub_; @@ -263,7 +263,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; - LayeredCostmap * layered_costmap_{nullptr}; + std::unique_ptr layered_costmap_{nullptr}; std::string name_; std::string parent_namespace_; void mapUpdateLoop(double frequency); diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp index d124eaf04c1..0873d8781ec 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp @@ -30,17 +30,11 @@ class CostmapSubscriber { public: CostmapSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & parent, const std::string & topic_name); CostmapSubscriber( - rclcpp::Node::SharedPtr node, - const std::string & topic_name); - - CostmapSubscriber( - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, + const rclcpp::Node::WeakPtr & parent, const std::string & topic_name); ~CostmapSubscriber() {} @@ -48,11 +42,6 @@ class CostmapSubscriber std::shared_ptr getCostmap(); protected: - // Interfaces used for logging and creating publishers and subscribers - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_; - rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_; - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_; - void toCostmap2D(); void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg); 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 acc3e7c2347..b6eef0c043e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp @@ -29,20 +29,12 @@ class FootprintSubscriber { public: FootprintSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & parent, const std::string & topic_name, const double & footprint_timeout); FootprintSubscriber( - rclcpp::Node::SharedPtr node, - const std::string & topic_name, - const double & footprint_timeout); - - FootprintSubscriber( - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, - const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, + const rclcpp::Node::WeakPtr & parent, const std::string & topic_name, const double & footprint_timeout); @@ -61,11 +53,7 @@ class FootprintSubscriber rclcpp::Time & stamp, rclcpp::Duration valid_footprint_timeout); protected: - // Interfaces used for logging and creating publishers and subscribers - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_; - rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_; - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_; - rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_; + rclcpp::Clock::SharedPtr clock_; void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg); diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp index b0eca7251a1..e2ff924e3ce 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp @@ -62,7 +62,7 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface LayeredCostmap * parent, std::string name, tf2_ros::Buffer * tf, - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & node, rclcpp::Node::SharedPtr client_node, rclcpp::Node::SharedPtr rclcpp_node); virtual void deactivate() {} /** @brief Stop publishers. */ @@ -123,7 +123,9 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface const std::vector & getFootprint() const; /** @brief Convenience functions for declaring ROS parameters */ - void declareParameter(const std::string & param_name, const rclcpp::ParameterValue & value); + void declareParameter( + const std::string & param_name, + const rclcpp::ParameterValue & value); bool hasParameter(const std::string & param_name); void undeclareAllParameters(); std::string getFullName(const std::string & param_name); @@ -132,9 +134,11 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface LayeredCostmap * layered_costmap_; std::string name_; tf2_ros::Buffer * tf_; - nav2_util::LifecycleNode::SharedPtr node_; rclcpp::Node::SharedPtr client_node_; rclcpp::Node::SharedPtr rclcpp_node_; + rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")}; /** @brief This is called at the end of initialize(). Override to * implement subclass-specific initialization. diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp index 4c816dad28f..30b03f33161 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp @@ -73,7 +73,7 @@ class ObservationBuffer * @param tf_tolerance The amount of time to wait for a transform to be available when setting a new global frame */ ObservationBuffer( - nav2_util::LifecycleNode::SharedPtr nh, + const nav2_util::LifecycleNode::WeakPtr & parent, std::string topic_name, double observation_keep_time, double expected_update_rate, @@ -142,10 +142,11 @@ class ObservationBuffer */ void purgeStaleObservations(); + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")}; tf2_ros::Buffer & tf2_buffer_; const rclcpp::Duration observation_keep_time_; const rclcpp::Duration expected_update_rate_; - nav2_util::LifecycleNode::SharedPtr nh_; rclcpp::Time last_updated_; std::string global_frame_; std::string sensor_frame_; diff --git a/nav2_costmap_2d/plugins/inflation_layer.cpp b/nav2_costmap_2d/plugins/inflation_layer.cpp index df8405a3c91..d6f89045dbb 100644 --- a/nav2_costmap_2d/plugins/inflation_layer.cpp +++ b/nav2_costmap_2d/plugins/inflation_layer.cpp @@ -82,11 +82,17 @@ InflationLayer::onInitialize() declareParameter("inflate_unknown", rclcpp::ParameterValue(false)); declareParameter("inflate_around_unknown", rclcpp::ParameterValue(false)); - node_->get_parameter(name_ + "." + "enabled", enabled_); - node_->get_parameter(name_ + "." + "inflation_radius", inflation_radius_); - node_->get_parameter(name_ + "." + "cost_scaling_factor", cost_scaling_factor_); - node_->get_parameter(name_ + "." + "inflate_unknown", inflate_unknown_); - node_->get_parameter(name_ + "." + "inflate_around_unknown", inflate_around_unknown_); + { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + node->get_parameter(name_ + "." + "enabled", enabled_); + node->get_parameter(name_ + "." + "inflation_radius", inflation_radius_); + node->get_parameter(name_ + "." + "cost_scaling_factor", cost_scaling_factor_); + node->get_parameter(name_ + "." + "inflate_unknown", inflate_unknown_); + node->get_parameter(name_ + "." + "inflate_around_unknown", inflate_around_unknown_); + } current_ = true; seen_.clear(); @@ -148,8 +154,7 @@ InflationLayer::onFootprintChanged() need_reinflation_ = true; RCLCPP_DEBUG( - rclcpp::get_logger( - "nav2_costmap_2d"), "InflationLayer::onFootprintChanged(): num footprint points: %lu," + logger_, "InflationLayer::onFootprintChanged(): num footprint points: %lu," " inscribed_radius_ = %.3f, inflation_radius_ = %.3f", layered_costmap_->getFootprint().size(), inscribed_radius_, inflation_radius_); } @@ -167,7 +172,7 @@ InflationLayer::updateCosts( // make sure the inflation list is empty at the beginning of the cycle (should always be true) for (auto & dist : inflation_cells_) { RCLCPP_FATAL_EXPRESSION( - rclcpp::get_logger("nav2_costmap_2d"), + logger_, !dist.empty(), "The inflation list must be empty at the beginning of inflation"); } @@ -176,8 +181,7 @@ InflationLayer::updateCosts( if (seen_.size() != size_x * size_y) { RCLCPP_WARN( - rclcpp::get_logger( - "nav2_costmap_2d"), "InflationLayer::updateCosts(): seen_ vector size is wrong"); + logger_, "InflationLayer::updateCosts(): seen_ vector size is wrong"); seen_ = std::vector(size_x * size_y, false); } diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index 7c911563578..c25097b3048 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -76,22 +76,27 @@ void ObstacleLayer::onInitialize() // TODO(mjeronimo): these four are candidates for dynamic update declareParameter("enabled", rclcpp::ParameterValue(true)); - declareParameter( - "footprint_clearing_enabled", - rclcpp::ParameterValue(true)); + declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(true)); declareParameter("max_obstacle_height", rclcpp::ParameterValue(2.0)); declareParameter("combination_method", rclcpp::ParameterValue(1)); declareParameter("observation_sources", rclcpp::ParameterValue(std::string(""))); - node_->get_parameter(name_ + "." + "enabled", enabled_); - node_->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); - node_->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_); - node_->get_parameter(name_ + "." + "combination_method", combination_method_); - node_->get_parameter("track_unknown_space", track_unknown_space); - node_->get_parameter("transform_tolerance", transform_tolerance); - node_->get_parameter(name_ + "." + "observation_sources", topics_string); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + node->get_parameter(name_ + "." + "enabled", enabled_); + node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); + node->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_); + node->get_parameter(name_ + "." + "combination_method", combination_method_); + node->get_parameter("track_unknown_space", track_unknown_space); + node->get_parameter("transform_tolerance", transform_tolerance); + node->get_parameter(name_ + "." + "observation_sources", topics_string); - RCLCPP_INFO(node_->get_logger(), "Subscribed to Topics: %s", topics_string.c_str()); + RCLCPP_INFO( + logger_, + "Subscribed to Topics: %s", topics_string.c_str()); rolling_window_ = layered_costmap_->isRolling(); @@ -129,24 +134,24 @@ void ObstacleLayer::onInitialize() declareParameter(source + "." + "obstacle_range", rclcpp::ParameterValue(2.5)); declareParameter(source + "." + "raytrace_range", rclcpp::ParameterValue(3.0)); - node_->get_parameter(name_ + "." + source + "." + "topic", topic); - node_->get_parameter(name_ + "." + source + "." + "sensor_frame", sensor_frame); - node_->get_parameter( + node->get_parameter(name_ + "." + source + "." + "topic", topic); + node->get_parameter(name_ + "." + source + "." + "sensor_frame", sensor_frame); + node->get_parameter( name_ + "." + source + "." + "observation_persistence", observation_keep_time); - node_->get_parameter( + node->get_parameter( name_ + "." + source + "." + "expected_update_rate", expected_update_rate); - node_->get_parameter(name_ + "." + source + "." + "data_type", data_type); - node_->get_parameter(name_ + "." + source + "." + "min_obstacle_height", min_obstacle_height); - node_->get_parameter(name_ + "." + source + "." + "max_obstacle_height", max_obstacle_height); - node_->get_parameter(name_ + "." + source + "." + "inf_is_valid", inf_is_valid); - node_->get_parameter(name_ + "." + source + "." + "marking", marking); - node_->get_parameter(name_ + "." + source + "." + "clearing", clearing); + node->get_parameter(name_ + "." + source + "." + "data_type", data_type); + node->get_parameter(name_ + "." + source + "." + "min_obstacle_height", min_obstacle_height); + node->get_parameter(name_ + "." + source + "." + "max_obstacle_height", max_obstacle_height); + node->get_parameter(name_ + "." + source + "." + "inf_is_valid", inf_is_valid); + node->get_parameter(name_ + "." + source + "." + "marking", marking); + node->get_parameter(name_ + "." + source + "." + "clearing", clearing); if (!(data_type == "PointCloud2" || data_type == "LaserScan")) { RCLCPP_FATAL( - node_->get_logger(), + logger_, "Only topics that use point cloud2s or laser scans are currently supported"); throw std::runtime_error( "Only topics that use point cloud2s or laser scans are currently supported"); @@ -154,14 +159,14 @@ void ObstacleLayer::onInitialize() // get the obstacle range for the sensor double obstacle_range; - node_->get_parameter(name_ + "." + source + "." + "obstacle_range", obstacle_range); + node->get_parameter(name_ + "." + source + "." + "obstacle_range", obstacle_range); // get the raytrace range for the sensor double raytrace_range; - node_->get_parameter(name_ + "." + source + "." + "raytrace_range", raytrace_range); + node->get_parameter(name_ + "." + source + "." + "raytrace_range", raytrace_range); RCLCPP_DEBUG( - node_->get_logger(), + logger_, "Creating an observation buffer for source %s, topic %s, frame %s", source.c_str(), topic.c_str(), sensor_frame.c_str()); @@ -171,7 +176,7 @@ void ObstacleLayer::onInitialize() std::shared_ptr( new ObservationBuffer( - node_, topic, observation_keep_time, expected_update_rate, + node, topic, observation_keep_time, expected_update_rate, min_obstacle_height, max_obstacle_height, obstacle_range, raytrace_range, *tf_, global_frame_, sensor_frame, transform_tolerance))); @@ -187,7 +192,7 @@ void ObstacleLayer::onInitialize() } RCLCPP_DEBUG( - node_->get_logger(), + logger_, "Created an observation buffer for source %s, topic %s, global frame: %s, " "expected update rate: %.2f, observation persistence: %.2f", source.c_str(), topic.c_str(), @@ -233,7 +238,7 @@ void ObstacleLayer::onInitialize() if (inf_is_valid) { RCLCPP_WARN( - node_->get_logger(), + logger_, "obstacle_layer: inf_is_valid option is not applicable to PointCloud observations."); } @@ -273,7 +278,7 @@ ObstacleLayer::laserScanCallback( projector_.transformLaserScanToPointCloud(message->header.frame_id, *message, cloud, *tf_); } catch (tf2::TransformException & ex) { RCLCPP_WARN( - node_->get_logger(), + logger_, "High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str(), ex.what()); @@ -310,7 +315,7 @@ ObstacleLayer::laserScanValidInfCallback( projector_.transformLaserScanToPointCloud(message.header.frame_id, message, cloud, *tf_); } catch (tf2::TransformException & ex) { RCLCPP_WARN( - node_->get_logger(), + logger_, "High fidelity enabled, but TF returned a transform exception to frame %s: %s", global_frame_.c_str(), ex.what()); projector_.projectLaser(message, cloud); @@ -382,7 +387,7 @@ ObstacleLayer::updateBounds( // if the obstacle is too high or too far away from the robot we won't add it if (pz > max_obstacle_height_) { - RCLCPP_DEBUG(node_->get_logger(), "The point is too high"); + RCLCPP_DEBUG(logger_, "The point is too high"); continue; } @@ -394,14 +399,14 @@ ObstacleLayer::updateBounds( // if the point is far enough away... we won't consider it if (sq_dist >= sq_obstacle_range) { - RCLCPP_DEBUG(node_->get_logger(), "The point is too far away"); + RCLCPP_DEBUG(logger_, "The point is too far away"); continue; } // now we need to compute the map coordinates for the observation unsigned int mx, my; if (!worldToMap(px, py, mx, my)) { - RCLCPP_DEBUG(node_->get_logger(), "Computing map coords failed"); + RCLCPP_DEBUG(logger_, "Computing map coords failed"); continue; } @@ -528,7 +533,7 @@ ObstacleLayer::raytraceFreespace( unsigned int x0, y0; if (!worldToMap(ox, oy, x0, y0)) { RCLCPP_WARN( - node_->get_logger(), + logger_, "Sensor origin at (%.2f, %.2f) is out of map bounds. The costmap cannot raytrace for it.", ox, oy); return; diff --git a/nav2_costmap_2d/plugins/range_sensor_layer.cpp b/nav2_costmap_2d/plugins/range_sensor_layer.cpp index 8a6124a47a9..ff71fa8edf1 100644 --- a/nav2_costmap_2d/plugins/range_sensor_layer.cpp +++ b/nav2_costmap_2d/plugins/range_sensor_layer.cpp @@ -61,45 +61,50 @@ void RangeSensorLayer::onInitialize() { current_ = true; buffered_readings_ = 0; - last_reading_time_ = node_->now(); + last_reading_time_ = clock_->now(); default_value_ = to_cost(0.5); matchSize(); resetRange(); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + declareParameter("enabled", rclcpp::ParameterValue(true)); - node_->get_parameter(name_ + "." + "enabled", enabled_); + node->get_parameter(name_ + "." + "enabled", enabled_); declareParameter("phi", rclcpp::ParameterValue(1.2)); - node_->get_parameter(name_ + "." + "phi", phi_v_); + node->get_parameter(name_ + "." + "phi", phi_v_); declareParameter("inflate_cone", rclcpp::ParameterValue(1.0)); - node_->get_parameter(name_ + "." + "phi", phi_v_); + node->get_parameter(name_ + "." + "phi", phi_v_); declareParameter("no_readings_timeout", rclcpp::ParameterValue(0.0)); - node_->get_parameter(name_ + "." + "no_readings_timeout", no_readings_timeout_); + node->get_parameter(name_ + "." + "no_readings_timeout", no_readings_timeout_); declareParameter("clear_threshold", rclcpp::ParameterValue(0.2)); - node_->get_parameter(name_ + "." + "clear_threshold", clear_threshold_); + node->get_parameter(name_ + "." + "clear_threshold", clear_threshold_); declareParameter("mark_threshold", rclcpp::ParameterValue(0.8)); - node_->get_parameter(name_ + "." + "mark_threshold", mark_threshold_); + node->get_parameter(name_ + "." + "mark_threshold", mark_threshold_); declareParameter("clear_on_max_reading", rclcpp::ParameterValue(false)); - node_->get_parameter(name_ + "." + "clear_on_max_reading", clear_on_max_reading_); + node->get_parameter(name_ + "." + "clear_on_max_reading", clear_on_max_reading_); double temp_tf_tol = 0.0; - node_->get_parameter("transform_tolerance", temp_tf_tol); + node->get_parameter("transform_tolerance", temp_tf_tol); transform_tolerance_ = tf2::durationFromSec(temp_tf_tol); std::vector topic_names{}; declareParameter("topics", rclcpp::ParameterValue(topic_names)); - node_->get_parameter(name_ + "." + "topics", topic_names); + node->get_parameter(name_ + "." + "topics", topic_names); InputSensorType input_sensor_type = InputSensorType::ALL; std::string sensor_type_name; declareParameter("input_sensor_type", rclcpp::ParameterValue("ALL")); - node_->get_parameter(name_ + "." + "input_sensor_type", sensor_type_name); + node->get_parameter(name_ + "." + "input_sensor_type", sensor_type_name); std::transform( sensor_type_name.begin(), sensor_type_name.end(), sensor_type_name.begin(), ::toupper); RCLCPP_INFO( - node_->get_logger(), "%s: %s as input_sensor_type given", + logger_, "%s: %s as input_sensor_type given", name_.c_str(), sensor_type_name.c_str()); if (sensor_type_name == "VARIABLE") { @@ -110,14 +115,14 @@ void RangeSensorLayer::onInitialize() input_sensor_type = InputSensorType::ALL; } else { RCLCPP_ERROR( - node_->get_logger(), "%s: Invalid input sensor type: %s. Defaulting to ALL.", + logger_, "%s: Invalid input sensor type: %s. Defaulting to ALL.", name_.c_str(), sensor_type_name.c_str()); } // Validate topic names list: it must be a (normally non-empty) list of strings if (topic_names.empty()) { RCLCPP_FATAL( - node_->get_logger(), "Invalid topic names list: it must" + logger_, "Invalid topic names list: it must" "be a non-empty list of strings"); return; } @@ -138,19 +143,19 @@ void RangeSensorLayer::onInitialize() std::placeholders::_1); } else { RCLCPP_ERROR( - node_->get_logger(), + logger_, "%s: Invalid input sensor type: %s. Did you make a new type" "and forgot to choose the subscriber for it?", name_.c_str(), sensor_type_name.c_str()); } range_subs_.push_back( - node_->create_subscription( + node->create_subscription( topic_name, rclcpp::SensorDataQoS(), std::bind( &RangeSensorLayer::bufferIncomingRangeMsg, this, std::placeholders::_1))); RCLCPP_INFO( - node_->get_logger(), "RangeSensorLayer: subscribed to " + logger_, "RangeSensorLayer: subscribed to " "topic %s", range_subs_.back()->get_topic_name()); } global_frame_ = layered_costmap_->getGlobalFrameID(); @@ -238,7 +243,7 @@ void RangeSensorLayer::processFixedRangeMsg(sensor_msgs::msg::Range & range_mess { if (!std::isinf(range_message.range)) { RCLCPP_ERROR( - node_->get_logger(), + logger_, "Fixed distance ranger (min_range == max_range) in frame %s sent invalid value. " "Only -Inf (== object detected) and Inf (== no object detected) are valid.", range_message.header.frame_id.c_str()); @@ -290,7 +295,7 @@ void RangeSensorLayer::updateCostmap( in.header.frame_id, global_frame_, tf2_ros::fromMsg(in.header.stamp))) { RCLCPP_INFO( - node_->get_logger(), "Range sensor layer can't transform from %s to %s", + logger_, "Range sensor layer can't transform from %s to %s", global_frame_.c_str(), in.header.frame_id.c_str()); return; } @@ -387,7 +392,7 @@ void RangeSensorLayer::updateCostmap( } buffered_readings_++; - last_reading_time_ = node_->now(); + last_reading_time_ = clock_->now(); } void RangeSensorLayer::update_cell( @@ -409,8 +414,12 @@ void RangeSensorLayer::update_cell( double prob_not = (1 - sensor) * (1 - prior); double new_prob = prob_occ / (prob_occ + prob_not); - RCLCPP_DEBUG(node_->get_logger(), "%f %f | %f %f = %f", dx, dy, theta, phi, sensor); - RCLCPP_DEBUG(node_->get_logger(), "%f | %f %f | %f", prior, prob_occ, prob_not, new_prob); + RCLCPP_DEBUG( + logger_, + "%f %f | %f %f = %f", dx, dy, theta, phi, sensor); + RCLCPP_DEBUG( + logger_, + "%f | %f %f | %f", prior, prob_occ, prob_not, new_prob); unsigned char c = to_cost(new_prob); setCost(x, y, c); } @@ -448,12 +457,13 @@ void RangeSensorLayer::updateBounds( if (buffered_readings_ == 0) { if (no_readings_timeout_ > 0.0 && - (node_->now() - last_reading_time_).seconds() > no_readings_timeout_) + (clock_->now() - last_reading_time_).seconds() > + no_readings_timeout_) { RCLCPP_WARN( - node_->get_logger(), "No range readings received for %.2f seconds, " - "while expected at least every %.2f seconds.", - (node_->now() - last_reading_time_).seconds(), + logger_, + "No range readings received for %.2f seconds, while expected at least every %.2f seconds.", + (clock_->now() - last_reading_time_).seconds(), no_readings_timeout_); current_ = false; } @@ -504,7 +514,7 @@ void RangeSensorLayer::updateCosts( void RangeSensorLayer::reset() { - RCLCPP_DEBUG(node_->get_logger(), "Reseting range sensor layer..."); + RCLCPP_DEBUG(logger_, "Reseting range sensor layer..."); deactivate(); resetMaps(); current_ = true; diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index cb3a01f1be4..e503126a4c2 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -40,10 +40,8 @@ #include "nav2_costmap_2d/static_layer.hpp" #include -#include #include -#include "nav2_costmap_2d/costmap_math.hpp" #include "pluginlib/class_list_macros.hpp" #include "tf2/convert.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.h" @@ -81,17 +79,23 @@ StaticLayer::onInitialize() } RCLCPP_INFO( - node_->get_logger(), + logger_, "Subscribing to the map topic (%s) with %s durability", map_topic_.c_str(), map_subscribe_transient_local_ ? "transient local" : "volatile"); - map_sub_ = node_->create_subscription( + + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + map_sub_ = node->create_subscription( map_topic_, map_qos, std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1)); if (subscribe_to_updates_) { - RCLCPP_INFO(node_->get_logger(), "Subscribing to updates"); - map_update_sub_ = node_->create_subscription( + RCLCPP_INFO(logger_, "Subscribing to updates"); + map_update_sub_ = node->create_subscription( map_topic_ + "_updates", rclcpp::SystemDefaultsQoS(), std::bind(&StaticLayer::incomingUpdate, this, std::placeholders::_1)); @@ -126,25 +130,30 @@ StaticLayer::getParameters() declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); declareParameter("map_topic", rclcpp::ParameterValue("")); - node_->get_parameter(name_ + "." + "enabled", enabled_); - node_->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + node->get_parameter(name_ + "." + "enabled", enabled_); + node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); std::string private_map_topic, global_map_topic; - node_->get_parameter(name_ + "." + "map_topic", private_map_topic); - node_->get_parameter("map_topic", global_map_topic); + node->get_parameter(name_ + "." + "map_topic", private_map_topic); + node->get_parameter("map_topic", global_map_topic); if (!private_map_topic.empty()) { map_topic_ = private_map_topic; } else { map_topic_ = global_map_topic; } - node_->get_parameter( + node->get_parameter( name_ + "." + "map_subscribe_transient_local", map_subscribe_transient_local_); - node_->get_parameter("track_unknown_space", track_unknown_space_); - node_->get_parameter("use_maximum", use_maximum_); - node_->get_parameter("lethal_cost_threshold", temp_lethal_threshold); - node_->get_parameter("unknown_cost_value", unknown_cost_value_); - node_->get_parameter("trinary_costmap", trinary_costmap_); - node_->get_parameter("transform_tolerance", temp_tf_tol); + node->get_parameter("track_unknown_space", track_unknown_space_); + node->get_parameter("use_maximum", use_maximum_); + node->get_parameter("lethal_cost_threshold", temp_lethal_threshold); + node->get_parameter("unknown_cost_value", unknown_cost_value_); + node->get_parameter("trinary_costmap", trinary_costmap_); + node->get_parameter("transform_tolerance", temp_tf_tol); // Enforce bounds lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0); @@ -157,13 +166,13 @@ StaticLayer::getParameters() void StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) { - RCLCPP_DEBUG(node_->get_logger(), "StaticLayer: Process map"); + RCLCPP_DEBUG(logger_, "StaticLayer: Process map"); unsigned int size_x = new_map.info.width; unsigned int size_y = new_map.info.height; RCLCPP_DEBUG( - node_->get_logger(), + logger_, "StaticLayer: Received a %d X %d map at %f m/pix", size_x, size_y, new_map.info.resolution); @@ -178,7 +187,7 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) { // Update the size of the layered costmap (and all layers, including this one) RCLCPP_INFO( - node_->get_logger(), + logger_, "StaticLayer: Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map.info.resolution); layered_costmap_->resizeMap( @@ -193,7 +202,7 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) { // only update the size of the costmap stored locally in this layer RCLCPP_INFO( - node_->get_logger(), + logger_, "StaticLayer: Resizing static layer to %d X %d at %f m/pix", size_x, size_y, new_map.info.resolution); resizeMap( @@ -282,7 +291,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u x_ + width_ < update->x + update->width) { RCLCPP_WARN( - node_->get_logger(), + logger_, "StaticLayer: Map update ignored. Exceeds bounds of static layer.\n" "Static layer origin: %d, %d bounds: %d X %d\n" "Update origin: %d, %d bounds: %d X %d", @@ -293,7 +302,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u if (update->header.frame_id != map_frame_) { RCLCPP_WARN( - node_->get_logger(), + logger_, "StaticLayer: Map update ignored. Current map is in frame %s " "but update was in frame %s", map_frame_.c_str(), update->header.frame_id.c_str()); @@ -370,7 +379,7 @@ StaticLayer::updateCosts( static int count = 0; // throttle warning down to only 1/10 message rate if (++count == 10) { - RCLCPP_WARN(node_->get_logger(), "Can't update static costmap layer, no map received"); + RCLCPP_WARN(logger_, "Can't update static costmap layer, no map received"); count = 0; } update_in_progress_.store(false); @@ -395,7 +404,7 @@ StaticLayer::updateCosts( map_frame_, global_frame_, tf2::TimePointZero, transform_tolerance_); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(node_->get_logger(), "StaticLayer: %s", ex.what()); + RCLCPP_ERROR(logger_, "StaticLayer: %s", ex.what()); update_in_progress_.store(false); return; } diff --git a/nav2_costmap_2d/plugins/voxel_layer.cpp b/nav2_costmap_2d/plugins/voxel_layer.cpp index 5235e236757..0d1eba32d30 100644 --- a/nav2_costmap_2d/plugins/voxel_layer.cpp +++ b/nav2_costmap_2d/plugins/voxel_layer.cpp @@ -72,27 +72,32 @@ void VoxelLayer::onInitialize() declareParameter("combination_method", rclcpp::ParameterValue(1)); declareParameter("publish_voxel_map", rclcpp::ParameterValue(false)); - node_->get_parameter(name_ + "." + "enabled", enabled_); - node_->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); - node_->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_); - node_->get_parameter(name_ + "." + "z_voxels", size_z_); - node_->get_parameter(name_ + "." + "origin_z", origin_z_); - node_->get_parameter(name_ + "." + "z_resolution", z_resolution_); - node_->get_parameter(name_ + "." + "unknown_threshold", unknown_threshold_); - node_->get_parameter(name_ + "." + "mark_threshold", mark_threshold_); - node_->get_parameter(name_ + "." + "combination_method", combination_method_); - node_->get_parameter(name_ + "." + "publish_voxel_map", publish_voxel_); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + node->get_parameter(name_ + "." + "enabled", enabled_); + node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); + node->get_parameter(name_ + "." + "max_obstacle_height", max_obstacle_height_); + node->get_parameter(name_ + "." + "z_voxels", size_z_); + node->get_parameter(name_ + "." + "origin_z", origin_z_); + node->get_parameter(name_ + "." + "z_resolution", z_resolution_); + node->get_parameter(name_ + "." + "unknown_threshold", unknown_threshold_); + node->get_parameter(name_ + "." + "mark_threshold", mark_threshold_); + node->get_parameter(name_ + "." + "combination_method", combination_method_); + node->get_parameter(name_ + "." + "publish_voxel_map", publish_voxel_); auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(); if (publish_voxel_) { - voxel_pub_ = node_->create_publisher( + voxel_pub_ = node->create_publisher( "voxel_grid", custom_qos); } voxel_pub_->on_activate(); - clearing_endpoints_pub_ = node_->create_publisher( + clearing_endpoints_pub_ = node->create_publisher( "clearing_endpoints", custom_qos); unknown_threshold_ += (VOXEL_BITS - size_z_); @@ -225,7 +230,7 @@ void VoxelLayer::updateBounds( grid_msg->resolutions.y = resolution_; grid_msg->resolutions.z = z_resolution_; grid_msg->header.frame_id = global_frame_; - grid_msg->header.stamp = node_->now(); + grid_msg->header.stamp = clock_->now(); voxel_pub_->publish(std::move(grid_msg)); } @@ -307,13 +312,22 @@ void VoxelLayer::raytraceFreespace( if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)) { RCLCPP_WARN( - node_->get_logger(), + logger_, "Sensor origin: (%.2f, %.2f, %.2f), out of map bounds. The costmap can't raytrace for it.", ox, oy, oz); return; } - bool publish_clearing_points = (node_->count_subscribers("clearing_endpoints") > 0); + bool publish_clearing_points; + + { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + publish_clearing_points = (node->count_subscribers("clearing_endpoints") > 0); + } + if (publish_clearing_points) { clearing_endpoints_->points.clear(); clearing_endpoints_->points.reserve(clearing_observation_cloud_size); diff --git a/nav2_costmap_2d/src/clear_costmap_service.cpp b/nav2_costmap_2d/src/clear_costmap_service.cpp index bdadecdaf2e..3ef9f63310f 100644 --- a/nav2_costmap_2d/src/clear_costmap_service.cpp +++ b/nav2_costmap_2d/src/clear_costmap_service.cpp @@ -32,27 +32,29 @@ using ClearAroundRobot = nav2_msgs::srv::ClearCostmapAroundRobot; using ClearEntirely = nav2_msgs::srv::ClearEntireCostmap; ClearCostmapService::ClearCostmapService( - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap) -: node_(node), costmap_(costmap) +: costmap_(costmap) { + auto node = parent.lock(); + logger_ = node->get_logger(); reset_value_ = costmap_.getCostmap()->getDefaultValue(); - node_->get_parameter("clearable_layers", clearable_layers_); + node->get_parameter("clearable_layers", clearable_layers_); - clear_except_service_ = node_->create_service( + clear_except_service_ = node->create_service( "clear_except_" + costmap_.getName(), std::bind( &ClearCostmapService::clearExceptRegionCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - clear_around_service_ = node_->create_service( + clear_around_service_ = node->create_service( "clear_around_" + costmap.getName(), std::bind( &ClearCostmapService::clearAroundRobotCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - clear_entire_service_ = node_->create_service( + clear_entire_service_ = node->create_service( "clear_entirely_" + costmap_.getName(), std::bind( &ClearCostmapService::clearEntireCallback, this, @@ -65,7 +67,7 @@ void ClearCostmapService::clearExceptRegionCallback( const shared_ptr/*response*/) { RCLCPP_INFO( - node_->get_logger(), + logger_, "Received request to clear except a region the " + costmap_.getName()); clearExceptRegion(request->reset_distance); @@ -77,7 +79,7 @@ void ClearCostmapService::clearAroundRobotCallback( const shared_ptr/*response*/) { RCLCPP_INFO( - node_->get_logger(), + logger_, "Received request to clear around robot the " + costmap_.getName()); if ((request->window_size_x == 0) || (request->window_size_y == 0)) { @@ -93,7 +95,9 @@ void ClearCostmapService::clearEntireCallback( const std::shared_ptr/*request*/, const std::shared_ptr/*response*/) { - RCLCPP_INFO(node_->get_logger(), "Received request to clear entirely the " + costmap_.getName()); + RCLCPP_INFO( + logger_, + "Received request to clear entirely the " + costmap_.getName()); clearEntirely(); } @@ -103,7 +107,9 @@ void ClearCostmapService::clearExceptRegion(const double reset_distance) double x, y; if (!getPosition(x, y)) { - RCLCPP_ERROR(node_->get_logger(), "Cannot clear map because robot pose cannot be retrieved."); + RCLCPP_ERROR( + logger_, + "Cannot clear map because robot pose cannot be retrieved."); return; } @@ -122,7 +128,9 @@ void ClearCostmapService::clearAroundRobot(double window_size_x, double window_s double pose_x, pose_y; if (!getPosition(pose_x, pose_y)) { - RCLCPP_ERROR(node_->get_logger(), "Cannot clear map because robot pose cannot be retrieved."); + RCLCPP_ERROR( + logger_, + "Cannot clear map because robot pose cannot be retrieved."); return; } diff --git a/nav2_costmap_2d/src/costmap_2d_publisher.cpp b/nav2_costmap_2d/src/costmap_2d_publisher.cpp index 56797e566b4..fde37a38150 100644 --- a/nav2_costmap_2d/src/costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/src/costmap_2d_publisher.cpp @@ -50,27 +50,35 @@ namespace nav2_costmap_2d char * Costmap2DPublisher::cost_translation_table_ = NULL; Costmap2DPublisher::Costmap2DPublisher( - nav2_util::LifecycleNode::SharedPtr ros_node, Costmap2D * costmap, + const nav2_util::LifecycleNode::WeakPtr & parent, + Costmap2D * costmap, std::string global_frame, std::string topic_name, bool always_send_full_costmap) -: node_(ros_node), costmap_(costmap), global_frame_(global_frame), topic_name_(topic_name), - active_(false), always_send_full_costmap_(always_send_full_costmap) +: costmap_(costmap), + global_frame_(global_frame), + topic_name_(topic_name), + active_(false), + always_send_full_costmap_(always_send_full_costmap) { + auto node = parent.lock(); + clock_ = node->get_clock(); + logger_ = node->get_logger(); + auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(); // TODO(bpwilcox): port onNewSubscription functionality for publisher - costmap_pub_ = node_->create_publisher( + costmap_pub_ = node->create_publisher( topic_name, custom_qos); - costmap_raw_pub_ = node_->create_publisher( + costmap_raw_pub_ = node->create_publisher( topic_name + "_raw", custom_qos); - costmap_update_pub_ = node_->create_publisher( + costmap_update_pub_ = node->create_publisher( topic_name + "_updates", custom_qos); // Create a service that will use the callback function to handle requests. - costmap_service_ = node_->create_service( + costmap_service_ = node->create_service( "get_costmap", std::bind( &Costmap2DPublisher::costmap_service_callback, this, std::placeholders::_1, std::placeholders::_2, @@ -150,7 +158,7 @@ void Costmap2DPublisher::prepareCostmap() costmap_raw_ = std::make_unique(); costmap_raw_->header.frame_id = global_frame_; - costmap_raw_->header.stamp = node_->now(); + costmap_raw_->header.stamp = clock_->now(); costmap_raw_->metadata.layer = "master"; costmap_raw_->metadata.resolution = resolution; @@ -175,7 +183,7 @@ void Costmap2DPublisher::prepareCostmap() void Costmap2DPublisher::publishCostmap() { - if (node_->count_subscribers(costmap_raw_pub_->get_topic_name()) > 0) { + if (costmap_raw_pub_->get_subscription_count() > 0) { prepareCostmap(); costmap_raw_pub_->publish(std::move(costmap_raw_)); } @@ -187,12 +195,12 @@ void Costmap2DPublisher::publishCostmap() saved_origin_x_ != costmap_->getOriginX() || saved_origin_y_ != costmap_->getOriginY()) { - if (node_->count_subscribers(costmap_pub_->get_topic_name()) > 0) { + if (costmap_pub_->get_subscription_count() > 0) { prepareGrid(); costmap_pub_->publish(std::move(grid_)); } } else if (x0_ < xn_) { - if (node_->count_subscribers(costmap_update_pub_->get_topic_name()) > 0) { + if (costmap_update_pub_->get_subscription_count() > 0) { std::unique_lock lock(*(costmap_->getMutex())); // Publish Just an Update auto update = std::make_unique(); @@ -225,7 +233,7 @@ Costmap2DPublisher::costmap_service_callback( const std::shared_ptr/*request*/, const std::shared_ptr response) { - RCLCPP_DEBUG(node_->get_logger(), "Received costmap service request"); + RCLCPP_DEBUG(logger_, "Received costmap service request"); // TODO(bpwilcox): Grab correct orientation information tf2::Quaternion quaternion; @@ -235,7 +243,7 @@ Costmap2DPublisher::costmap_service_callback( auto size_y = costmap_->getSizeInCellsY(); auto data_length = size_x * size_y; unsigned char * data = costmap_->getCharMap(); - auto current_time = node_->now(); + auto current_time = clock_->now(); response->map.header.stamp = current_time; response->map.header.frame_id = global_frame_; diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index b172bd87df2..a66383fa50a 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -116,7 +116,6 @@ Costmap2DROS::Costmap2DROS( Costmap2DROS::~Costmap2DROS() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn @@ -126,7 +125,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) getParameters(); // Create the costmap itself - layered_costmap_ = new LayeredCostmap(global_frame_, rolling_window_, track_unknown_space_); + layered_costmap_ = std::make_unique( + global_frame_, rolling_window_, track_unknown_space_); if (!layered_costmap_->isSizeLocked()) { layered_costmap_->resizeMap( @@ -151,7 +151,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) // TODO(mjeronimo): instead of get(), use a shared ptr plugin->initialize( - layered_costmap_, plugin_names_[i], tf_buffer_.get(), + layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(), shared_from_this(), client_node_, rclcpp_node_); RCLCPP_INFO(get_logger(), "Initialized plugin \"%s\"", plugin_names_[i].c_str()); @@ -166,7 +166,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) footprint_pub_ = create_publisher( "published_footprint", rclcpp::SystemDefaultsQoS()); - costmap_publisher_ = new Costmap2DPublisher( + costmap_publisher_ = std::make_unique( shared_from_this(), layered_costmap_->getCostmap(), global_frame_, "costmap", always_send_full_costmap_); @@ -255,8 +255,7 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); - delete layered_costmap_; - layered_costmap_ = nullptr; + layered_costmap_.reset(); tf_listener_.reset(); tf_buffer_.reset(); @@ -264,11 +263,7 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/) footprint_sub_.reset(); footprint_pub_.reset(); - if (costmap_publisher_ != nullptr) { - delete costmap_publisher_; - costmap_publisher_ = nullptr; - } - + costmap_publisher_.reset(); clear_costmap_service_.reset(); return nav2_util::CallbackReturn::SUCCESS; diff --git a/nav2_costmap_2d/src/costmap_subscriber.cpp b/nav2_costmap_2d/src/costmap_subscriber.cpp index 18d9efc3fdf..37b99bb5980 100644 --- a/nav2_costmap_2d/src/costmap_subscriber.cpp +++ b/nav2_costmap_2d/src/costmap_subscriber.cpp @@ -21,35 +21,25 @@ namespace nav2_costmap_2d { CostmapSubscriber::CostmapSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & parent, const std::string & topic_name) -: CostmapSubscriber(node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_logging_interface(), - topic_name) -{} - -CostmapSubscriber::CostmapSubscriber( - rclcpp::Node::SharedPtr node, - const std::string & topic_name) -: CostmapSubscriber(node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_logging_interface(), - topic_name) -{} +: topic_name_(topic_name) +{ + auto node = parent.lock(); + costmap_sub_ = node->create_subscription( + topic_name_, + rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), + std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1)); +} CostmapSubscriber::CostmapSubscriber( - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, + const rclcpp::Node::WeakPtr & parent, const std::string & topic_name) -: node_base_(node_base), - node_topics_(node_topics), - node_logging_(node_logging), - topic_name_(topic_name) +: topic_name_(topic_name) { - costmap_sub_ = rclcpp::create_subscription( - node_topics_, topic_name_, + auto node = parent.lock(); + costmap_sub_ = node->create_subscription( + topic_name_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1)); } diff --git a/nav2_costmap_2d/src/footprint_subscriber.cpp b/nav2_costmap_2d/src/footprint_subscriber.cpp index 242c7aec372..29a275d0348 100644 --- a/nav2_costmap_2d/src/footprint_subscriber.cpp +++ b/nav2_costmap_2d/src/footprint_subscriber.cpp @@ -22,43 +22,29 @@ namespace nav2_costmap_2d { FootprintSubscriber::FootprintSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + const nav2_util::LifecycleNode::WeakPtr & parent, const std::string & topic_name, const double & footprint_timeout) -: FootprintSubscriber(node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_logging_interface(), - node->get_node_clock_interface(), - topic_name, footprint_timeout) -{} - -FootprintSubscriber::FootprintSubscriber( - rclcpp::Node::SharedPtr node, - const std::string & topic_name, - const double & footprint_timeout) -: FootprintSubscriber(node->get_node_base_interface(), - node->get_node_topics_interface(), - node->get_node_logging_interface(), - node->get_node_clock_interface(), - topic_name, footprint_timeout) -{} +: topic_name_(topic_name), + footprint_timeout_(rclcpp::Duration::from_seconds(footprint_timeout)) +{ + auto node = parent.lock(); + clock_ = node->get_clock(); + footprint_sub_ = node->create_subscription( + topic_name, rclcpp::SystemDefaultsQoS(), + std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1)); +} FootprintSubscriber::FootprintSubscriber( - const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, - const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics, - const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, - const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, + const rclcpp::Node::WeakPtr & parent, const std::string & topic_name, const double & footprint_timeout) -: node_base_(node_base), - node_topics_(node_topics), - node_logging_(node_logging), - node_clock_(node_clock), - topic_name_(topic_name), +: topic_name_(topic_name), footprint_timeout_(rclcpp::Duration::from_seconds(footprint_timeout)) { - footprint_sub_ = rclcpp::create_subscription( - node_topics_, + auto node = parent.lock(); + clock_ = node->get_clock(); + footprint_sub_ = node->create_subscription( topic_name, rclcpp::SystemDefaultsQoS(), std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1)); } @@ -89,7 +75,7 @@ FootprintSubscriber::getFootprint( std::vector & footprint, rclcpp::Duration & valid_footprint_timeout) { - rclcpp::Time t = node_clock_->get_clock()->now(); + rclcpp::Time t = clock_->now(); return getFootprint(footprint, t, valid_footprint_timeout); } diff --git a/nav2_costmap_2d/src/layer.cpp b/nav2_costmap_2d/src/layer.cpp index 228c060f70d..bdfe0e51164 100644 --- a/nav2_costmap_2d/src/layer.cpp +++ b/nav2_costmap_2d/src/layer.cpp @@ -46,17 +46,25 @@ Layer::Layer() void Layer::initialize( - LayeredCostmap * parent, std::string name, tf2_ros::Buffer * tf, - nav2_util::LifecycleNode::SharedPtr node, + LayeredCostmap * parent, + std::string name, + tf2_ros::Buffer * tf, + const nav2_util::LifecycleNode::WeakPtr & node, rclcpp::Node::SharedPtr client_node, rclcpp::Node::SharedPtr rclcpp_node) { layered_costmap_ = parent; name_ = name; tf_ = tf; - node_ = node; client_node_ = client_node; rclcpp_node_ = rclcpp_node; + node_ = node; + + { + auto node_shared_ptr = node_.lock(); + logger_ = node_shared_ptr->get_logger(); + clock_ = node_shared_ptr->get_clock(); + } onInitialize(); } @@ -69,23 +77,37 @@ Layer::getFootprint() const void Layer::declareParameter( - const std::string & param_name, const rclcpp::ParameterValue & value) + const std::string & param_name, + const rclcpp::ParameterValue & value) { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } local_params_.insert(param_name); - nav2_util::declare_parameter_if_not_declared(node_, getFullName(param_name), value); + nav2_util::declare_parameter_if_not_declared( + node, getFullName(param_name), value); } bool Layer::hasParameter(const std::string & param_name) { - return node_->has_parameter(getFullName(param_name)); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + return node->has_parameter(getFullName(param_name)); } void Layer::undeclareAllParameters() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } for (auto & param_name : local_params_) { - node_->undeclare_parameter(getFullName(param_name)); + node->undeclare_parameter(getFullName(param_name)); } local_params_.clear(); } diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp index c0086ebb9bc..e771b2f96f0 100644 --- a/nav2_costmap_2d/src/observation_buffer.cpp +++ b/nav2_costmap_2d/src/observation_buffer.cpp @@ -47,19 +47,26 @@ namespace nav2_costmap_2d { ObservationBuffer::ObservationBuffer( - nav2_util::LifecycleNode::SharedPtr nh, std::string topic_name, double observation_keep_time, + const nav2_util::LifecycleNode::WeakPtr & parent, + std::string topic_name, + double observation_keep_time, double expected_update_rate, double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range, tf2_ros::Buffer & tf2_buffer, std::string global_frame, std::string sensor_frame, double tf_tolerance) : tf2_buffer_(tf2_buffer), observation_keep_time_(rclcpp::Duration::from_seconds(observation_keep_time)), - expected_update_rate_(rclcpp::Duration::from_seconds(expected_update_rate)), nh_(nh), - last_updated_(nh->now()), global_frame_(global_frame), sensor_frame_(sensor_frame), + expected_update_rate_(rclcpp::Duration::from_seconds(expected_update_rate)), + global_frame_(global_frame), + sensor_frame_(sensor_frame), topic_name_(topic_name), min_obstacle_height_(min_obstacle_height), max_obstacle_height_(max_obstacle_height), obstacle_range_(obstacle_range), raytrace_range_(raytrace_range), tf_tolerance_(tf_tolerance) { + auto node = parent.lock(); + clock_ = node->get_clock(); + logger_ = node->get_logger(); + last_updated_ = node->now(); } ObservationBuffer::~ObservationBuffer() @@ -68,7 +75,7 @@ ObservationBuffer::~ObservationBuffer() bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame) { - rclcpp::Time transform_time = nh_->now(); + rclcpp::Time transform_time = clock_->now(); std::string tf_error; geometry_msgs::msg::TransformStamped transformStamped; @@ -77,8 +84,7 @@ bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame) tf2::durationFromSec(tf_tolerance_), &tf_error)) { RCLCPP_ERROR( - rclcpp::get_logger( - "nav2_costmap_2d"), "Transform between %s and %s with tolerance %.2f failed: %s.", + logger_, "Transform between %s and %s with tolerance %.2f failed: %s.", new_global_frame.c_str(), global_frame_.c_str(), tf_tolerance_, tf_error.c_str()); return false; @@ -103,8 +109,7 @@ bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame) *(obs.cloud_), *(obs.cloud_), new_global_frame, tf2::durationFromSec(tf_tolerance_)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR( - rclcpp::get_logger( - "nav2_costmap_2d"), "TF Error attempting to transform an observation from %s to %s: %s", + logger_, "TF Error attempting to transform an observation from %s to %s: %s", global_frame_.c_str(), new_global_frame.c_str(), ex.what()); return false; @@ -191,8 +196,7 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud) // if an exception occurs, we need to remove the empty observation from the list observation_list_.pop_front(); RCLCPP_ERROR( - rclcpp::get_logger( - "nav2_costmap_2d"), + logger_, "TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s", sensor_frame_.c_str(), cloud.header.frame_id.c_str(), ex.what()); @@ -200,7 +204,7 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud) } // if the update was successful, we want to update the last updated time - last_updated_ = nh_->now(); + last_updated_ = clock_->now(); // we'll also remove any stale observations from the list purgeStaleObservations(); @@ -234,7 +238,9 @@ void ObservationBuffer::purgeStaleObservations() Observation & obs = *obs_it; // check if the observation is out of date... and if it is, // remove it and those that follow from the list - if ((nh_->now() - obs.cloud_->header.stamp) > observation_keep_time_) { + if ((clock_->now() - obs.cloud_->header.stamp) > + observation_keep_time_) + { observation_list_.erase(obs_it, observation_list_.end()); return; } @@ -248,20 +254,22 @@ bool ObservationBuffer::isCurrent() const return true; } - bool current = (nh_->now() - last_updated_) <= expected_update_rate_; + bool current = (clock_->now() - last_updated_) <= + expected_update_rate_; if (!current) { RCLCPP_WARN( - rclcpp::get_logger( - "nav2_costmap_2d"), - "The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.", //NOLINT + logger_, + "The %s observation buffer has not been updated for %.2f seconds, " + "and it should be updated every %.2f seconds.", topic_name_.c_str(), - (nh_->now() - last_updated_).seconds(), expected_update_rate_.seconds()); + (clock_->now() - last_updated_).seconds(), + expected_update_rate_.seconds()); } return current; } void ObservationBuffer::resetLastUpdated() { - last_updated_ = nh_->now(); + last_updated_ = clock_->now(); } } // namespace nav2_costmap_2d diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp index 2da4b44a52c..ec80f5045fe 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp @@ -67,7 +67,7 @@ class DWBLocalPlanner : public nav2_core::Controller DWBLocalPlanner(); void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr & tf, const std::shared_ptr & costmap_ros) override; @@ -182,10 +182,12 @@ class DWBLocalPlanner : public nav2_core::Controller * @param name The namespace of this planner. */ virtual void loadCritics(); - void loadBackwardsCompatibleParameters(); - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; + rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("DWBLocalPlanner")}; + std::shared_ptr tf_; std::shared_ptr costmap_ros_; diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp index c8bfe27d4f9..aba5354c652 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp @@ -69,7 +69,9 @@ namespace dwb_core class DWBPublisher { public: - explicit DWBPublisher(nav2_util::LifecycleNode::SharedPtr node, const std::string & plugin_name); + explicit DWBPublisher( + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const std::string & plugin_name); nav2_util::CallbackReturn on_configure(); nav2_util::CallbackReturn on_activate(); @@ -124,7 +126,8 @@ class DWBPublisher std::shared_ptr> marker_pub_; std::shared_ptr> cost_grid_pc_pub_; - nav2_util::LifecycleNode::SharedPtr node_; + rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + rclcpp::Clock::SharedPtr clock_; std::string plugin_name_; }; diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp index 98594af1f4d..d204bc52c25 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp @@ -97,16 +97,16 @@ class TrajectoryCritic std::string & ns, std::shared_ptr costmap_ros) { + node_ = nh; name_ = name; costmap_ros_ = costmap_ros; - nh_ = nh; dwb_plugin_name_ = ns; - if (!nh_->has_parameter(dwb_plugin_name_ + "." + name_ + ".scale")) { - nh_->declare_parameter( + if (!nh->has_parameter(dwb_plugin_name_ + "." + name_ + ".scale")) { + nh->declare_parameter( dwb_plugin_name_ + "." + name_ + ".scale", rclcpp::ParameterValue(1.0)); } - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_); + nh->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_); onInit(); } virtual void onInit() {} @@ -181,7 +181,7 @@ class TrajectoryCritic std::string dwb_plugin_name_; std::shared_ptr costmap_ros_; double scale_; - nav2_util::LifecycleNode::SharedPtr nh_; + rclcpp_lifecycle::LifecycleNode::WeakPtr node_; }; } // namespace dwb_core diff --git a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp index 245323db510..4b68eafd49c 100644 --- a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp +++ b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp @@ -64,61 +64,65 @@ DWBLocalPlanner::DWBLocalPlanner() } void DWBLocalPlanner::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr & tf, const std::shared_ptr & costmap_ros) { - node_ = node; + node_ = parent; + auto node = node_.lock(); + + logger_ = node->get_logger(); + clock_ = node->get_clock(); costmap_ros_ = costmap_ros; tf_ = tf; dwb_plugin_name_ = name; - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".critics"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".default_critic_namespaces"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".critics"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".default_critic_namespaces"); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".prune_plan", + node, dwb_plugin_name_ + ".prune_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".prune_distance", + node, dwb_plugin_name_ + ".prune_distance", rclcpp::ParameterValue(1.0)); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".debug_trajectory_details", + node, dwb_plugin_name_ + ".debug_trajectory_details", rclcpp::ParameterValue(false)); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".trajectory_generator_name", + node, dwb_plugin_name_ + ".trajectory_generator_name", rclcpp::ParameterValue(std::string("dwb_plugins::StandardTrajectoryGenerator"))); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".transform_tolerance", + node, dwb_plugin_name_ + ".transform_tolerance", rclcpp::ParameterValue(0.1)); declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + ".short_circuit_trajectory_evaluation", + node, dwb_plugin_name_ + ".short_circuit_trajectory_evaluation", rclcpp::ParameterValue(true)); std::string traj_generator_name; double transform_tolerance; - node_->get_parameter(dwb_plugin_name_ + ".transform_tolerance", transform_tolerance); + node->get_parameter(dwb_plugin_name_ + ".transform_tolerance", transform_tolerance); transform_tolerance_ = rclcpp::Duration::from_seconds(transform_tolerance); - RCLCPP_INFO(node_->get_logger(), "Setting transform_tolerance to %f", transform_tolerance); + RCLCPP_INFO(logger_, "Setting transform_tolerance to %f", transform_tolerance); - node_->get_parameter(dwb_plugin_name_ + ".prune_plan", prune_plan_); - node_->get_parameter(dwb_plugin_name_ + ".prune_distance", prune_distance_); - node_->get_parameter(dwb_plugin_name_ + ".debug_trajectory_details", debug_trajectory_details_); - node_->get_parameter(dwb_plugin_name_ + ".trajectory_generator_name", traj_generator_name); - node_->get_parameter( + node->get_parameter(dwb_plugin_name_ + ".prune_plan", prune_plan_); + node->get_parameter(dwb_plugin_name_ + ".prune_distance", prune_distance_); + node->get_parameter(dwb_plugin_name_ + ".debug_trajectory_details", debug_trajectory_details_); + node->get_parameter(dwb_plugin_name_ + ".trajectory_generator_name", traj_generator_name); + node->get_parameter( dwb_plugin_name_ + ".short_circuit_trajectory_evaluation", short_circuit_trajectory_evaluation_); - pub_ = std::make_unique(node_, dwb_plugin_name_); + pub_ = std::make_unique(node, dwb_plugin_name_); pub_->on_configure(); traj_generator_ = traj_gen_loader_.createUniqueInstance(traj_generator_name); - traj_generator_->initialize(node_, dwb_plugin_name_); + traj_generator_->initialize(node, dwb_plugin_name_); try { loadCritics(); } catch (const std::exception & e) { - RCLCPP_ERROR(node_->get_logger(), "Couldn't load critics! Caught exception: %s", e.what()); + RCLCPP_ERROR(logger_, "Couldn't load critics! Caught exception: %s", e.what()); throw; } } @@ -164,40 +168,45 @@ DWBLocalPlanner::resolveCriticClassName(std::string base_name) void DWBLocalPlanner::loadCritics() { - node_->get_parameter(dwb_plugin_name_ + ".default_critic_namespaces", default_critic_namespaces_); - if (default_critic_namespaces_.size() == 0) { - default_critic_namespaces_.push_back("dwb_critics"); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + node->get_parameter(dwb_plugin_name_ + ".default_critic_namespaces", default_critic_namespaces_); + if (default_critic_namespaces_.empty()) { + default_critic_namespaces_.emplace_back("dwb_critics"); } std::vector critic_names; - if (!node_->get_parameter(dwb_plugin_name_ + ".critics", critic_names)) { + if (!node->get_parameter(dwb_plugin_name_ + ".critics", critic_names)) { loadBackwardsCompatibleParameters(); } - node_->get_parameter(dwb_plugin_name_ + ".critics", critic_names); + node->get_parameter(dwb_plugin_name_ + ".critics", critic_names); for (unsigned int i = 0; i < critic_names.size(); i++) { std::string critic_plugin_name = critic_names[i]; std::string plugin_class; declare_parameter_if_not_declared( - node_, dwb_plugin_name_ + "." + critic_plugin_name + ".class", + node, dwb_plugin_name_ + "." + critic_plugin_name + ".class", rclcpp::ParameterValue(critic_plugin_name)); - node_->get_parameter(dwb_plugin_name_ + "." + critic_plugin_name + ".class", plugin_class); + node->get_parameter(dwb_plugin_name_ + "." + critic_plugin_name + ".class", plugin_class); plugin_class = resolveCriticClassName(plugin_class); TrajectoryCritic::Ptr plugin = critic_loader_.createUniqueInstance(plugin_class); RCLCPP_INFO( - node_->get_logger(), + logger_, "Using critic \"%s\" (%s)", critic_plugin_name.c_str(), plugin_class.c_str()); critics_.push_back(plugin); try { - plugin->initialize(node_, critic_plugin_name, dwb_plugin_name_, costmap_ros_); + plugin->initialize(node, critic_plugin_name, dwb_plugin_name_, costmap_ros_); } catch (const std::exception & e) { - RCLCPP_ERROR(node_->get_logger(), "Couldn't initialize critic plugin!"); + RCLCPP_ERROR(logger_, "Couldn't initialize critic plugin!"); throw; } - RCLCPP_INFO(node_->get_logger(), "Critic plugin initialized"); + RCLCPP_INFO(logger_, "Critic plugin initialized"); } } @@ -206,50 +215,55 @@ DWBLocalPlanner::loadBackwardsCompatibleParameters() { std::vector critic_names; RCLCPP_INFO( - node_->get_logger(), + logger_, "DWBLocalPlanner", "No critics configured! Using the default set."); - critic_names.push_back("RotateToGoal"); // discards trajectories that move forward when - // already at goal - critic_names.push_back("Oscillation"); // discards oscillating motions (assisgns cost -1) - critic_names.push_back("ObstacleFootprint"); // discards trajectories that move into obstacles - critic_names.push_back("GoalAlign"); // prefers trajectories that make the - // nose go towards (local) nose goal - critic_names.push_back("PathAlign"); // prefers trajectories that keep the - // robot nose on nose path - critic_names.push_back("PathDist"); // prefers trajectories on global path - critic_names.push_back("GoalDist"); // prefers trajectories that go towards - // (local) goal, based on wave propagation - node_->set_parameters({rclcpp::Parameter(dwb_plugin_name_ + ".critics", critic_names)}); - - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".path_distance_bias"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".goal_distance_bias"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".occdist_scale"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".max_scaling_factor"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".scaling_speed"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".PathAlign.scale"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".GoalAlign.scale"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".PathDist.scale"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".GoalDist.scale"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".ObstacleFootprint.scale"); + critic_names.emplace_back("RotateToGoal"); // discards trajectories that move forward when + // already at goal + critic_names.emplace_back("Oscillation"); // discards oscillating motions (assisgns cost -1) + critic_names.emplace_back("ObstacleFootprint"); // discards trajectories that move into obstacles + critic_names.emplace_back("GoalAlign"); // prefers trajectories that make the + // nose go towards (local) nose goal + critic_names.emplace_back("PathAlign"); // prefers trajectories that keep the + // robot nose on nose path + critic_names.emplace_back("PathDist"); // prefers trajectories on global path + critic_names.emplace_back("GoalDist"); // prefers trajectories that go towards + // (local) goal, based on wave propagation + + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + node->set_parameters({rclcpp::Parameter(dwb_plugin_name_ + ".critics", critic_names)}); + + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".path_distance_bias"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".goal_distance_bias"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".occdist_scale"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".max_scaling_factor"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".scaling_speed"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".PathAlign.scale"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".GoalAlign.scale"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".PathDist.scale"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".GoalDist.scale"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".ObstacleFootprint.scale"); declare_parameter_if_not_declared( - node_, - dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor"); - declare_parameter_if_not_declared(node_, dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed"); + node, dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor"); + declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed"); /* *INDENT-OFF* */ - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".path_distance_bias", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".path_distance_bias", dwb_plugin_name_ + ".PathAlign.scale", 32.0, false); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".goal_distance_bias", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".goal_distance_bias", dwb_plugin_name_ + ".GoalAlign.scale", 24.0, false); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".path_distance_bias", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".path_distance_bias", dwb_plugin_name_ + ".PathDist.scale", 32.0); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".goal_distance_bias", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".goal_distance_bias", dwb_plugin_name_ + ".GoalDist.scale", 24.0); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".occdist_scale", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".occdist_scale", dwb_plugin_name_ + ".ObstacleFootprint.scale", 0.01); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".max_scaling_factor", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".max_scaling_factor", dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor", 0.2); - nav_2d_utils::moveParameter(node_, dwb_plugin_name_ + ".scaling_speed", + nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".scaling_speed", dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed", 0.25); /* *INDENT-ON* */ } @@ -258,7 +272,7 @@ void DWBLocalPlanner::setPlan(const nav_msgs::msg::Path & path) { auto path2d = nav_2d_utils::pathToPath2D(path); - for (TrajectoryCritic::Ptr critic : critics_) { + for (TrajectoryCritic::Ptr & critic : critics_) { critic->reset(); } @@ -317,7 +331,7 @@ DWBLocalPlanner::computeVelocityCommands( { if (results) { results->header.frame_id = pose.header.frame_id; - results->header.stamp = node_->now(); + results->header.stamp = clock_->now(); } nav_2d_msgs::msg::Path2D transformed_plan; @@ -328,8 +342,8 @@ DWBLocalPlanner::computeVelocityCommands( nav2_costmap_2d::Costmap2D * costmap = costmap_ros_->getCostmap(); std::unique_lock lock(*(costmap->getMutex())); - for (TrajectoryCritic::Ptr critic : critics_) { - if (critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan) == false) { + for (TrajectoryCritic::Ptr & critic : critics_) { + if (!critic->prepare(pose.pose, velocity, goal_pose.pose, transformed_plan)) { RCLCPP_WARN(rclcpp::get_logger("DWBLocalPlanner"), "A scoring function failed to prepare"); } } @@ -339,11 +353,11 @@ DWBLocalPlanner::computeVelocityCommands( // Return Value nav_2d_msgs::msg::Twist2DStamped cmd_vel; - cmd_vel.header.stamp = node_->now(); + cmd_vel.header.stamp = clock_->now(); cmd_vel.velocity = best.traj.velocity; // debrief stateful scoring functions - for (TrajectoryCritic::Ptr critic : critics_) { + for (TrajectoryCritic::Ptr & critic : critics_) { critic->debrief(cmd_vel.velocity); } @@ -357,7 +371,7 @@ DWBLocalPlanner::computeVelocityCommands( nav_2d_msgs::msg::Twist2D empty_cmd; dwb_msgs::msg::Trajectory2D empty_traj; // debrief stateful scoring functions - for (TrajectoryCritic::Ptr critic : critics_) { + for (TrajectoryCritic::Ptr & critic : critics_) { critic->debrief(empty_cmd); } @@ -446,7 +460,7 @@ DWBLocalPlanner::scoreTrajectory( dwb_msgs::msg::TrajectoryScore score; score.traj = traj; - for (TrajectoryCritic::Ptr critic : critics_) { + for (TrajectoryCritic::Ptr & critic : critics_) { dwb_msgs::msg::CriticScore cs; cs.name = critic->getName(); cs.scale = critic->getScale(); @@ -484,7 +498,7 @@ nav_2d_msgs::msg::Path2D DWBLocalPlanner::transformGlobalPlan( const nav_2d_msgs::msg::Pose2DStamped & pose) { - if (global_plan_.poses.size() == 0) { + if (global_plan_.poses.empty()) { throw nav2_core::PlannerException("Received plan with zero length"); } @@ -580,7 +594,7 @@ DWBLocalPlanner::transformGlobalPlan( pub_->publishGlobalPlan(global_plan_); } - if (transformed_plan.poses.size() == 0) { + if (transformed_plan.poses.empty()) { throw nav2_core::PlannerException("Resulting plan has 0 poses in it."); } return transformed_plan; diff --git a/nav2_dwb_controller/dwb_core/src/publisher.cpp b/nav2_dwb_controller/dwb_core/src/publisher.cpp index 7f7ceb62c35..3e5e9b31f96 100644 --- a/nav2_dwb_controller/dwb_core/src/publisher.cpp +++ b/nav2_dwb_controller/dwb_core/src/publisher.cpp @@ -54,52 +54,61 @@ namespace dwb_core { DWBPublisher::DWBPublisher( - nav2_util::LifecycleNode::SharedPtr node, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) -: node_(node), plugin_name_(plugin_name) +: node_(parent), + plugin_name_(plugin_name) { + auto node = node_.lock(); + clock_ = node->get_clock(); +} + +nav2_util::CallbackReturn +DWBPublisher::on_configure() +{ + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + declare_parameter_if_not_declared( - node_, plugin_name + ".publish_evaluation", + node, plugin_name_ + ".publish_evaluation", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, plugin_name + ".publish_global_plan", + node, plugin_name_ + ".publish_global_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, plugin_name + ".publish_transformed_plan", + node, plugin_name_ + ".publish_transformed_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, plugin_name + ".publish_local_plan", + node, plugin_name_ + ".publish_local_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, plugin_name + ".publish_trajectories", + node, plugin_name_ + ".publish_trajectories", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared( - node_, plugin_name + ".publish_cost_grid_pc", + node, plugin_name_ + ".publish_cost_grid_pc", rclcpp::ParameterValue(false)); declare_parameter_if_not_declared( - node_, plugin_name + ".marker_lifetime", + node, plugin_name_ + ".marker_lifetime", rclcpp::ParameterValue(0.1)); -} -nav2_util::CallbackReturn -DWBPublisher::on_configure() -{ - node_->get_parameter(plugin_name_ + ".publish_evaluation", publish_evaluation_); - node_->get_parameter(plugin_name_ + ".publish_global_plan", publish_global_plan_); - node_->get_parameter(plugin_name_ + ".publish_transformed_plan", publish_transformed_); - node_->get_parameter(plugin_name_ + ".publish_local_plan", publish_local_plan_); - node_->get_parameter(plugin_name_ + ".publish_trajectories", publish_trajectories_); - node_->get_parameter(plugin_name_ + ".publish_cost_grid_pc", publish_cost_grid_pc_); - - eval_pub_ = node_->create_publisher("evaluation", 1); - global_pub_ = node_->create_publisher("received_global_plan", 1); - transformed_pub_ = node_->create_publisher("transformed_global_plan", 1); - local_pub_ = node_->create_publisher("local_plan", 1); - marker_pub_ = node_->create_publisher("marker", 1); - cost_grid_pc_pub_ = node_->create_publisher("cost_cloud", 1); + node->get_parameter(plugin_name_ + ".publish_evaluation", publish_evaluation_); + node->get_parameter(plugin_name_ + ".publish_global_plan", publish_global_plan_); + node->get_parameter(plugin_name_ + ".publish_transformed_plan", publish_transformed_); + node->get_parameter(plugin_name_ + ".publish_local_plan", publish_local_plan_); + node->get_parameter(plugin_name_ + ".publish_trajectories", publish_trajectories_); + node->get_parameter(plugin_name_ + ".publish_cost_grid_pc", publish_cost_grid_pc_); + + eval_pub_ = node->create_publisher("evaluation", 1); + global_pub_ = node->create_publisher("received_global_plan", 1); + transformed_pub_ = node->create_publisher("transformed_global_plan", 1); + local_pub_ = node->create_publisher("local_plan", 1); + marker_pub_ = node->create_publisher("marker", 1); + cost_grid_pc_pub_ = node->create_publisher("cost_cloud", 1); double marker_lifetime = 0.0; - node_->get_parameter(plugin_name_ + ".marker_lifetime", marker_lifetime); + node->get_parameter(plugin_name_ + ".marker_lifetime", marker_lifetime); marker_lifetime_ = rclcpp::Duration::from_seconds(marker_lifetime); return nav2_util::CallbackReturn::SUCCESS; @@ -147,7 +156,7 @@ DWBPublisher::on_cleanup() void DWBPublisher::publishEvaluation(std::shared_ptr results) { - if (node_->count_subscribers(eval_pub_->get_topic_name()) < 1) {return;} + if (eval_pub_->get_subscription_count() < 1) {return;} if (results == nullptr) {return;} @@ -162,7 +171,7 @@ DWBPublisher::publishEvaluation(std::shared_ptrcount_subscribers(marker_pub_->get_topic_name()) < 1) {return;} + if (marker_pub_->get_subscription_count() < 1) {return;} if (!publish_trajectories_) {return;} auto ma = std::make_unique(); @@ -235,7 +244,8 @@ DWBPublisher::publishLocalPlan( nav_2d_utils::poses2DToPath( traj.poses, header.frame_id, header.stamp)); - if (node_->count_subscribers(local_pub_->get_topic_name()) > 0) { + + if (local_pub_->get_subscription_count() > 0) { local_pub_->publish(std::move(path)); } } @@ -245,13 +255,13 @@ DWBPublisher::publishCostGrid( const std::shared_ptr costmap_ros, const std::vector critics) { - if (node_->count_subscribers(cost_grid_pc_pub_->get_topic_name()) < 1) {return;} + if (cost_grid_pc_pub_->get_subscription_count() < 1) {return;} if (!publish_cost_grid_pc_) {return;} auto cost_grid_pc = std::make_unique(); cost_grid_pc->header.frame_id = costmap_ros->getGlobalFrameID(); - cost_grid_pc->header.stamp = node_->now(); + cost_grid_pc->header.stamp = clock_->now(); nav2_costmap_2d::Costmap2D * costmap = costmap_ros->getCostmap(); double x_coord, y_coord; @@ -315,7 +325,7 @@ DWBPublisher::publishGenericPlan( const nav_2d_msgs::msg::Path2D plan, rclcpp::Publisher & pub, bool flag) { - if (node_->count_subscribers(pub.get_topic_name()) < 1) {return;} + if (pub.get_subscription_count() < 1) {return;} if (!flag) {return;} auto path = std::make_unique(nav_2d_utils::pathToPath(plan)); pub.publish(std::move(path)); diff --git a/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp b/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp index 538ddc7d294..457213b5024 100644 --- a/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp +++ b/nav2_dwb_controller/dwb_critics/include/dwb_critics/oscillation.hpp @@ -152,6 +152,7 @@ class OscillationCritic : public dwb_core::TrajectoryCritic geometry_msgs::msg::Pose2D pose_, prev_stationary_pose_; // Saved timestamp rclcpp::Time prev_reset_time_; + rclcpp::Clock::SharedPtr clock_; }; } // namespace dwb_critics diff --git a/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp b/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp index b3870343cdc..e409b86ce4e 100644 --- a/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp +++ b/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp @@ -47,10 +47,15 @@ void BaseObstacleCritic::onInit() { costmap_ = costmap_ros_->getCostmap(); + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + nav2_util::declare_parameter_if_not_declared( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".sum_scores", rclcpp::ParameterValue(false)); - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".sum_scores", sum_scores_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".sum_scores", sum_scores_); } double BaseObstacleCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) diff --git a/nav2_dwb_controller/dwb_critics/src/goal_align.cpp b/nav2_dwb_controller/dwb_critics/src/goal_align.cpp index d234d277623..6ff25bfa939 100644 --- a/nav2_dwb_controller/dwb_critics/src/goal_align.cpp +++ b/nav2_dwb_controller/dwb_critics/src/goal_align.cpp @@ -46,8 +46,14 @@ void GoalAlignCritic::onInit() { GoalDistCritic::onInit(); stop_on_failure_ = false; + + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + forward_point_distance_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".forward_point_distance", 0.325); } diff --git a/nav2_dwb_controller/dwb_critics/src/map_grid.cpp b/nav2_dwb_controller/dwb_critics/src/map_grid.cpp index bcfc5c44e66..c70f7125e4c 100644 --- a/nav2_dwb_controller/dwb_critics/src/map_grid.cpp +++ b/nav2_dwb_controller/dwb_critics/src/map_grid.cpp @@ -61,13 +61,18 @@ void MapGridCritic::onInit() // Always set to true, but can be overriden by subclasses stop_on_failure_ = true; + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + nav2_util::declare_parameter_if_not_declared( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".aggregation_type", rclcpp::ParameterValue(std::string("last"))); std::string aggro_str; - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".aggregation_type", aggro_str); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".aggregation_type", aggro_str); std::transform(aggro_str.begin(), aggro_str.end(), aggro_str.begin(), ::tolower); if (aggro_str == "last") { aggregationType_ = ScoreAggregationType::Last; diff --git a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp index e7ff9c6fb80..450f5b9751d 100644 --- a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp +++ b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp @@ -91,20 +91,27 @@ bool OscillationCritic::CommandTrend::hasSignFlipped() void OscillationCritic::onInit() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + clock_ = node->get_clock(); + oscillation_reset_dist_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".oscillation_reset_dist", 0.05); oscillation_reset_dist_sq_ = oscillation_reset_dist_ * oscillation_reset_dist_; oscillation_reset_angle_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".oscillation_reset_angle", 0.2); oscillation_reset_time_ = rclcpp::Duration::from_seconds( nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".oscillation_reset_time", -1.0)); nav2_util::declare_parameter_if_not_declared( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".x_only_threshold", rclcpp::ParameterValue(0.05)); /** @@ -114,23 +121,23 @@ void OscillationCritic::onInit() * If min_trans_vel is set in the namespace, as it used to be used for trajectory generation, complain then use that. * Otherwise, set x_only_threshold_ to 0.05 */ - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".x_only_threshold", x_only_threshold_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".x_only_threshold", x_only_threshold_); // TODO(crdelsey): How to handle searchParam? // std::string resolved_name; - // if (nh_->hasParam("x_only_threshold")) + // if (node->hasParam("x_only_threshold")) // { - // nh_->param("x_only_threshold", x_only_threshold_); + // node->param("x_only_threshold", x_only_threshold_); // } - // else if (nh_->searchParam("min_speed_xy", resolved_name)) + // else if (node->searchParam("min_speed_xy", resolved_name)) // { - // nh_->param(resolved_name, x_only_threshold_); + // node->param(resolved_name, x_only_threshold_); // } - // else if (nh_->searchParam("min_trans_vel", resolved_name)) + // else if (node->searchParam("min_trans_vel", resolved_name)) // { // ROS_WARN_NAMED("OscillationCritic", // "Parameter min_trans_vel is deprecated. " // "Please use the name min_speed_xy or x_only_threshold instead."); - // nh_->param(resolved_name, x_only_threshold_); + // node->param(resolved_name, x_only_threshold_); // } // else // { @@ -154,7 +161,7 @@ void OscillationCritic::debrief(const nav_2d_msgs::msg::Twist2D & cmd_vel) { if (setOscillationFlags(cmd_vel)) { prev_stationary_pose_ = pose_; - prev_reset_time_ = nh_->now(); + prev_reset_time_ = clock_->now(); } // if we've got restrictions... check if we can reset any oscillation flags @@ -183,7 +190,7 @@ bool OscillationCritic::resetAvailable() } } if (oscillation_reset_time_ >= rclcpp::Duration::from_seconds(0.0)) { - auto t_diff = (nh_->now() - prev_reset_time_); + auto t_diff = (clock_->now() - prev_reset_time_); if (t_diff > oscillation_reset_time_) { return true; } diff --git a/nav2_dwb_controller/dwb_critics/src/path_align.cpp b/nav2_dwb_controller/dwb_critics/src/path_align.cpp index 952d4561c04..23c9dfb2350 100644 --- a/nav2_dwb_controller/dwb_critics/src/path_align.cpp +++ b/nav2_dwb_controller/dwb_critics/src/path_align.cpp @@ -46,8 +46,14 @@ void PathAlignCritic::onInit() { PathDistCritic::onInit(); stop_on_failure_ = false; + + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + forward_point_distance_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".forward_point_distance", 0.325); } diff --git a/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp b/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp index 584e339c8ec..53fdee4fd64 100644 --- a/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp +++ b/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp @@ -46,23 +46,28 @@ namespace dwb_critics void PreferForwardCritic::onInit() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + declare_parameter_if_not_declared( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".penalty", rclcpp::ParameterValue(1.0)); declare_parameter_if_not_declared( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".strafe_x", rclcpp::ParameterValue(0.1)); declare_parameter_if_not_declared( - nh_, dwb_plugin_name_ + "." + name_ + ".strafe_theta", + node, dwb_plugin_name_ + "." + name_ + ".strafe_theta", rclcpp::ParameterValue(0.2)); declare_parameter_if_not_declared( - nh_, dwb_plugin_name_ + "." + name_ + ".theta_scale", + node, dwb_plugin_name_ + "." + name_ + ".theta_scale", rclcpp::ParameterValue(10.0)); - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".penalty", penalty_); - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".strafe_x", strafe_x_); - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".strafe_theta", strafe_theta_); - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".theta_scale", theta_scale_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".penalty", penalty_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".strafe_x", strafe_x_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".strafe_theta", strafe_theta_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".theta_scale", theta_scale_); } double PreferForwardCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) diff --git a/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp b/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp index 71683ebc8d8..7a46a0340e9 100644 --- a/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp +++ b/nav2_dwb_controller/dwb_critics/src/rotate_to_goal.cpp @@ -53,19 +53,24 @@ inline double hypot_sq(double dx, double dy) void RotateToGoalCritic::onInit() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + xy_goal_tolerance_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + ".xy_goal_tolerance", 0.25); xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_; double stopped_xy_velocity = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + ".trans_stopped_velocity", 0.25); stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity; slowing_factor_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".slowing_factor", 5.0); lookahead_time_ = nav_2d_utils::searchAndGetParam( - nh_, + node, dwb_plugin_name_ + "." + name_ + ".lookahead_time", -1.0); reset(); } diff --git a/nav2_dwb_controller/dwb_critics/src/twirling.cpp b/nav2_dwb_controller/dwb_critics/src/twirling.cpp index 3615e6f036e..7973cc09792 100644 --- a/nav2_dwb_controller/dwb_critics/src/twirling.cpp +++ b/nav2_dwb_controller/dwb_critics/src/twirling.cpp @@ -39,8 +39,12 @@ namespace dwb_critics { void TwirlingCritic::onInit() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } // Scale is set to 0 by default, so if it was not set otherwise, set to 0 - nh_->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_); + node->get_parameter(dwb_plugin_name_ + "." + name_ + ".scale", scale_); } double TwirlingCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) diff --git a/nav2_map_server/src/map_saver/map_saver.cpp b/nav2_map_server/src/map_saver/map_saver.cpp index 1bc50c512c2..c56d98ea666 100644 --- a/nav2_map_server/src/map_saver/map_saver.cpp +++ b/nav2_map_server/src/map_saver/map_saver.cpp @@ -55,7 +55,6 @@ MapSaver::MapSaver() MapSaver::~MapSaver() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn diff --git a/nav2_map_server/src/map_server/map_server.cpp b/nav2_map_server/src/map_server/map_server.cpp index 2e2e9453ab2..a0b140463f2 100644 --- a/nav2_map_server/src/map_server/map_server.cpp +++ b/nav2_map_server/src/map_server/map_server.cpp @@ -75,7 +75,6 @@ MapServer::MapServer() MapServer::~MapServer() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn diff --git a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp index e9d34279a56..5f2a8613259 100644 --- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp +++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp @@ -42,7 +42,7 @@ class NavfnPlanner : public nav2_core::GlobalPlanner // plugin configure void configure( - rclcpp_lifecycle::LifecycleNode::SharedPtr parent, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -119,8 +119,11 @@ class NavfnPlanner : public nav2_core::GlobalPlanner // TF buffer std::shared_ptr tf_; - // node ptr - nav2_util::LifecycleNode::SharedPtr node_; + // Clock + rclcpp::Clock::SharedPtr clock_; + + // Logger + rclcpp::Logger logger_{rclcpp::get_logger("NavfnPlanner")}; // Global Costmap nav2_costmap_2d::Costmap2D * costmap_; diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index a873a3e5d1c..2258b5e19f8 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -50,34 +50,37 @@ NavfnPlanner::NavfnPlanner() NavfnPlanner::~NavfnPlanner() { RCLCPP_INFO( - node_->get_logger(), "Destroying plugin %s of type NavfnPlanner", + logger_, "Destroying plugin %s of type NavfnPlanner", name_.c_str()); } void NavfnPlanner::configure( - rclcpp_lifecycle::LifecycleNode::SharedPtr parent, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { - node_ = parent; tf_ = tf; name_ = name; costmap_ = costmap_ros->getCostmap(); global_frame_ = costmap_ros->getGlobalFrameID(); + auto node = parent.lock(); + clock_ = node->get_clock(); + logger_ = node->get_logger(); + RCLCPP_INFO( - node_->get_logger(), "Configuring plugin %s of type NavfnPlanner", + logger_, "Configuring plugin %s of type NavfnPlanner", name_.c_str()); // Initialize parameters // Declare this plugin's parameters - declare_parameter_if_not_declared(node_, name + ".tolerance", rclcpp::ParameterValue(0.5)); - node_->get_parameter(name + ".tolerance", tolerance_); - declare_parameter_if_not_declared(node_, name + ".use_astar", rclcpp::ParameterValue(false)); - node_->get_parameter(name + ".use_astar", use_astar_); - declare_parameter_if_not_declared(node_, name + ".allow_unknown", rclcpp::ParameterValue(true)); - node_->get_parameter(name + ".allow_unknown", allow_unknown_); + declare_parameter_if_not_declared(node, name + ".tolerance", rclcpp::ParameterValue(0.5)); + node->get_parameter(name + ".tolerance", tolerance_); + declare_parameter_if_not_declared(node, name + ".use_astar", rclcpp::ParameterValue(false)); + node->get_parameter(name + ".use_astar", use_astar_); + declare_parameter_if_not_declared(node, name + ".allow_unknown", rclcpp::ParameterValue(true)); + node->get_parameter(name + ".allow_unknown", allow_unknown_); // Create a planner based on the new costmap size planner_ = std::make_unique( @@ -89,7 +92,7 @@ void NavfnPlanner::activate() { RCLCPP_INFO( - node_->get_logger(), "Activating plugin %s of type NavfnPlanner", + logger_, "Activating plugin %s of type NavfnPlanner", name_.c_str()); } @@ -97,7 +100,7 @@ void NavfnPlanner::deactivate() { RCLCPP_INFO( - node_->get_logger(), "Deactivating plugin %s of type NavfnPlanner", + logger_, "Deactivating plugin %s of type NavfnPlanner", name_.c_str()); } @@ -105,7 +108,7 @@ void NavfnPlanner::cleanup() { RCLCPP_INFO( - node_->get_logger(), "Cleaning up plugin %s of type NavfnPlanner", + logger_, "Cleaning up plugin %s of type NavfnPlanner", name_.c_str()); planner_.reset(); } @@ -125,7 +128,7 @@ nav_msgs::msg::Path NavfnPlanner::createPlan( if (!makePlan(start.pose, goal.pose, tolerance_, path)) { RCLCPP_WARN( - node_->get_logger(), "%s: failed to create plan with " + logger_, "%s: failed to create plan with " "tolerance %.2f.", name_.c_str(), tolerance_); } return path; @@ -152,7 +155,7 @@ NavfnPlanner::makePlan( // clear the plan, just in case plan.poses.clear(); - plan.header.stamp = node_->now(); + plan.header.stamp = clock_->now(); plan.header.frame_id = global_frame_; // TODO(orduno): add checks for start and goal reference frame -- should be in global frame @@ -161,13 +164,13 @@ NavfnPlanner::makePlan( double wy = start.position.y; RCLCPP_DEBUG( - node_->get_logger(), "Making plan from (%.2f,%.2f) to (%.2f,%.2f)", + logger_, "Making plan from (%.2f,%.2f) to (%.2f,%.2f)", start.position.x, start.position.y, goal.position.x, goal.position.y); unsigned int mx, my; if (!worldToMap(wx, wy, mx, my)) { RCLCPP_WARN( - node_->get_logger(), + logger_, "Cannot create a plan: the robot's start position is off the global" " costmap. Planning will always fail, are you sure" " the robot has been properly localized?"); @@ -197,7 +200,7 @@ NavfnPlanner::makePlan( if (!worldToMap(wx, wy, mx, my)) { RCLCPP_WARN( - node_->get_logger(), + logger_, "The goal sent to the planner is off the global costmap." " Planning will always fail to this goal."); return false; @@ -257,7 +260,7 @@ NavfnPlanner::makePlan( smoothApproachToGoal(best_pose, plan); } else { RCLCPP_ERROR( - node_->get_logger(), + logger_, "Failed to create a plan from potential when a legal" " potential was found. This shouldn't happen."); } @@ -305,7 +308,7 @@ NavfnPlanner::getPlanFromPotential( unsigned int mx, my; if (!worldToMap(wx, wy, mx, my)) { RCLCPP_WARN( - node_->get_logger(), + logger_, "The goal sent to the navfn planner is off the global costmap." " Planning will always fail to this goal."); return false; @@ -323,7 +326,9 @@ NavfnPlanner::getPlanFromPotential( } auto cost = planner_->getLastPathCost(); - RCLCPP_DEBUG(node_->get_logger(), "Path found, %d steps, %f cost\n", path_len, cost); + RCLCPP_DEBUG( + logger_, + "Path found, %d steps, %f cost\n", path_len, cost); // extract the plan float * x = planner_->getPathX(); @@ -415,7 +420,8 @@ NavfnPlanner::worldToMap(double wx, double wy, unsigned int & mx, unsigned int & } RCLCPP_ERROR( - node_->get_logger(), "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my, + logger_, + "worldToMap failed: mx,my: %d,%d, size_x,size_y: %d,%d", mx, my, costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()); return false; diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index ba264d6214c..701852d78a3 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -65,7 +65,6 @@ PlannerServer::PlannerServer() PlannerServer::~PlannerServer() { - RCLCPP_INFO(get_logger(), "Destroying"); planners_.clear(); costmap_thread_.reset(); } @@ -313,10 +312,7 @@ void PlannerServer::publishPlan(const nav_msgs::msg::Path & path) { auto msg = std::make_unique(path); - if ( - plan_publisher_->is_activated() && - this->count_subscribers(plan_publisher_->get_topic_name()) > 0) - { + if (plan_publisher_->is_activated() && plan_publisher_->get_subscription_count() > 0) { plan_publisher_->publish(std::move(msg)); } } diff --git a/nav2_recoveries/include/nav2_recoveries/recovery.hpp b/nav2_recoveries/include/nav2_recoveries/recovery.hpp index 174382b4ddf..b52d944884e 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery.hpp @@ -86,28 +86,32 @@ class Recovery : public nav2_core::Recovery } void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr parent, + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf, std::shared_ptr collision_checker) override { - RCLCPP_INFO(parent->get_logger(), "Configuring %s", name.c_str()); - node_ = parent; + auto node = node_.lock(); + + logger_ = node->get_logger(); + + RCLCPP_INFO(logger_, "Configuring %s", name.c_str()); + recovery_name_ = name; tf_ = tf; - node_->get_parameter("cycle_frequency", cycle_frequency_); - node_->get_parameter("global_frame", global_frame_); - node_->get_parameter("robot_base_frame", robot_base_frame_); - node_->get_parameter("transform_tolerance", transform_tolerance_); + node->get_parameter("cycle_frequency", cycle_frequency_); + node->get_parameter("global_frame", global_frame_); + node->get_parameter("robot_base_frame", robot_base_frame_); + node->get_parameter("transform_tolerance", transform_tolerance_); action_server_ = std::make_shared( - node_, recovery_name_, + node, recovery_name_, std::bind(&Recovery::execute, this)); collision_checker_ = collision_checker; - vel_pub_ = node_->create_publisher("cmd_vel", 1); + vel_pub_ = node->create_publisher("cmd_vel", 1); onConfigure(); } @@ -121,7 +125,7 @@ class Recovery : public nav2_core::Recovery void activate() override { - RCLCPP_INFO(node_->get_logger(), "Activating %s", recovery_name_.c_str()); + RCLCPP_INFO(logger_, "Activating %s", recovery_name_.c_str()); vel_pub_->on_activate(); action_server_->activate(); @@ -136,7 +140,8 @@ class Recovery : public nav2_core::Recovery } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; + rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + std::string recovery_name_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr vel_pub_; std::shared_ptr action_server_; @@ -152,25 +157,40 @@ class Recovery : public nav2_core::Recovery // Clock rclcpp::Clock steady_clock_{RCL_STEADY_TIME}; + // Logger + rclcpp::Logger logger_{rclcpp::get_logger("nav2_recoveries")}; + void execute() { - RCLCPP_INFO(node_->get_logger(), "Attempting %s", recovery_name_.c_str()); + RCLCPP_INFO(logger_, "Attempting %s", recovery_name_.c_str()); if (!enabled_) { - RCLCPP_WARN(node_->get_logger(), "Called while inactive, ignoring request."); + RCLCPP_WARN( + logger_, + "Called while inactive, ignoring request."); return; } if (onRun(action_server_->get_current_goal()) != Status::SUCCEEDED) { - RCLCPP_INFO(node_->get_logger(), "Initial checks failed for %s", recovery_name_.c_str()); + RCLCPP_INFO( + logger_, + "Initial checks failed for %s", recovery_name_.c_str()); action_server_->terminate_current(); return; } // Log a message every second - auto timer = node_->create_wall_timer( - 1s, - [&]() {RCLCPP_INFO(node_->get_logger(), "%s running...", recovery_name_.c_str());}); + { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + auto timer = node->create_wall_timer( + 1s, + [&]() + {RCLCPP_INFO(logger_, "%s running...", recovery_name_.c_str());}); + } auto start_time = steady_clock_.now(); @@ -181,7 +201,7 @@ class Recovery : public nav2_core::Recovery while (rclcpp::ok()) { if (action_server_->is_cancel_requested()) { - RCLCPP_INFO(node_->get_logger(), "Canceling %s", recovery_name_.c_str()); + RCLCPP_INFO(logger_, "Canceling %s", recovery_name_.c_str()); stopRobot(); result->total_elapsed_time = steady_clock_.now() - start_time; action_server_->terminate_all(result); @@ -191,7 +211,7 @@ class Recovery : public nav2_core::Recovery // TODO(orduno) #868 Enable preempting a Recovery on-the-fly without stopping if (action_server_->is_preempt_requested()) { RCLCPP_ERROR( - node_->get_logger(), "Received a preemption request for %s," + logger_, "Received a preemption request for %s," " however feature is currently not implemented. Aborting and stopping.", recovery_name_.c_str()); stopRobot(); @@ -202,13 +222,15 @@ class Recovery : public nav2_core::Recovery switch (onCycleUpdate()) { case Status::SUCCEEDED: - RCLCPP_INFO(node_->get_logger(), "%s completed successfully", recovery_name_.c_str()); + RCLCPP_INFO( + logger_, + "%s completed successfully", recovery_name_.c_str()); result->total_elapsed_time = steady_clock_.now() - start_time; action_server_->succeeded_current(result); return; case Status::FAILED: - RCLCPP_WARN(node_->get_logger(), "%s failed", recovery_name_.c_str()); + RCLCPP_WARN(logger_, "%s failed", recovery_name_.c_str()); result->total_elapsed_time = steady_clock_.now() - start_time; action_server_->terminate_current(result); return; diff --git a/nav2_recoveries/include/nav2_recoveries/recovery_server.hpp b/nav2_recoveries/include/nav2_recoveries/recovery_server.hpp index bb9efa571c1..5df52c16ca5 100644 --- a/nav2_recoveries/include/nav2_recoveries/recovery_server.hpp +++ b/nav2_recoveries/include/nav2_recoveries/recovery_server.hpp @@ -51,8 +51,8 @@ class RecoveryServer : public nav2_util::LifecycleNode std::shared_ptr transform_listener_; // Plugins - std::vector> recoveries_; pluginlib::ClassLoader plugin_loader_; + std::vector> recoveries_; std::vector default_ids_; std::vector default_types_; std::vector recovery_ids_; diff --git a/nav2_recoveries/plugins/back_up.cpp b/nav2_recoveries/plugins/back_up.cpp index fae91b998c5..91baa7ba823 100644 --- a/nav2_recoveries/plugins/back_up.cpp +++ b/nav2_recoveries/plugins/back_up.cpp @@ -37,18 +37,23 @@ BackUp::~BackUp() void BackUp::onConfigure() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + nav2_util::declare_parameter_if_not_declared( - node_, + node, "simulate_ahead_time", rclcpp::ParameterValue(2.0)); - node_->get_parameter("simulate_ahead_time", simulate_ahead_time_); + node->get_parameter("simulate_ahead_time", simulate_ahead_time_); } Status BackUp::onRun(const std::shared_ptr command) { if (command->target.y != 0.0 || command->target.z != 0.0) { RCLCPP_INFO( - node_->get_logger(), "Backing up in Y and Z not supported, " - "will only move in X."); + logger_, + "Backing up in Y and Z not supported, will only move in X."); } // Silently ensure that both the speed and direction are positive. @@ -59,7 +64,7 @@ Status BackUp::onRun(const std::shared_ptr command) initial_pose_, *tf_, global_frame_, robot_base_frame_, transform_tolerance_)) { - RCLCPP_ERROR(node_->get_logger(), "Initial robot pose is not available."); + RCLCPP_ERROR(logger_, "Initial robot pose is not available."); return Status::FAILED; } @@ -73,7 +78,7 @@ Status BackUp::onCycleUpdate() current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_)) { - RCLCPP_ERROR(node_->get_logger(), "Current robot pose is not available."); + RCLCPP_ERROR(logger_, "Current robot pose is not available."); return Status::FAILED; } @@ -102,7 +107,7 @@ Status BackUp::onCycleUpdate() if (!isCollisionFree(distance, cmd_vel.get(), pose2d)) { stopRobot(); - RCLCPP_WARN(node_->get_logger(), "Collision Ahead - Exiting BackUp"); + RCLCPP_WARN(logger_, "Collision Ahead - Exiting BackUp"); return Status::SUCCEEDED; } diff --git a/nav2_recoveries/plugins/spin.cpp b/nav2_recoveries/plugins/spin.cpp index e24be17d899..011d1c00960 100644 --- a/nav2_recoveries/plugins/spin.cpp +++ b/nav2_recoveries/plugins/spin.cpp @@ -47,25 +47,30 @@ Spin::~Spin() void Spin::onConfigure() { + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + nav2_util::declare_parameter_if_not_declared( - node_, + node, "simulate_ahead_time", rclcpp::ParameterValue(2.0)); - node_->get_parameter("simulate_ahead_time", simulate_ahead_time_); + node->get_parameter("simulate_ahead_time", simulate_ahead_time_); nav2_util::declare_parameter_if_not_declared( - node_, + node, "max_rotational_vel", rclcpp::ParameterValue(1.0)); - node_->get_parameter("max_rotational_vel", max_rotational_vel_); + node->get_parameter("max_rotational_vel", max_rotational_vel_); nav2_util::declare_parameter_if_not_declared( - node_, + node, "min_rotational_vel", rclcpp::ParameterValue(0.4)); - node_->get_parameter("min_rotational_vel", min_rotational_vel_); + node->get_parameter("min_rotational_vel", min_rotational_vel_); nav2_util::declare_parameter_if_not_declared( - node_, + node, "rotational_acc_lim", rclcpp::ParameterValue(3.2)); - node_->get_parameter("rotational_acc_lim", rotational_acc_lim_); + node->get_parameter("rotational_acc_lim", rotational_acc_lim_); } Status Spin::onRun(const std::shared_ptr command) @@ -75,7 +80,7 @@ Status Spin::onRun(const std::shared_ptr command) current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_)) { - RCLCPP_ERROR(node_->get_logger(), "Current robot pose is not available."); + RCLCPP_ERROR(logger_, "Current robot pose is not available."); return Status::FAILED; } @@ -84,7 +89,7 @@ Status Spin::onRun(const std::shared_ptr command) cmd_yaw_ = command->target_yaw; RCLCPP_INFO( - node_->get_logger(), "Turning %0.2f for spin recovery.", + logger_, "Turning %0.2f for spin recovery.", cmd_yaw_); return Status::SUCCEEDED; } @@ -96,7 +101,7 @@ Status Spin::onCycleUpdate() current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_)) { - RCLCPP_ERROR(node_->get_logger(), "Current robot pose is not available."); + RCLCPP_ERROR(logger_, "Current robot pose is not available."); return Status::FAILED; } @@ -132,7 +137,7 @@ Status Spin::onCycleUpdate() if (!isCollisionFree(relative_yaw_, cmd_vel.get(), pose2d)) { stopRobot(); - RCLCPP_WARN(node_->get_logger(), "Collision Ahead - Exiting Spin"); + RCLCPP_WARN(logger_, "Collision Ahead - Exiting Spin"); return Status::SUCCEEDED; } diff --git a/nav2_recoveries/src/recovery_server.cpp b/nav2_recoveries/src/recovery_server.cpp index 3f108edb438..981c0c44fbd 100644 --- a/nav2_recoveries/src/recovery_server.cpp +++ b/nav2_recoveries/src/recovery_server.cpp @@ -58,6 +58,7 @@ RecoveryServer::RecoveryServer() RecoveryServer::~RecoveryServer() { + recoveries_.clear(); } nav2_util::CallbackReturn diff --git a/nav2_util/include/nav2_util/odometry_utils.hpp b/nav2_util/include/nav2_util/odometry_utils.hpp index 9a1d49d5047..f75d01ebefb 100644 --- a/nav2_util/include/nav2_util/odometry_utils.hpp +++ b/nav2_util/include/nav2_util/odometry_utils.hpp @@ -43,14 +43,14 @@ class OdomSmoother public: /** * @brief Constructor that subscribes to an Odometry topic - * @param nh NodeHandle for creating subscriber + * @param parent NodeHandle for creating subscriber * @param filter_duration Duration for odom history (seconds) * @param odom_topic Topic on which odometry should be received */ explicit OdomSmoother( - rclcpp::Node::SharedPtr nh, + const rclcpp::Node::WeakPtr & parent, double filter_duration = 0.3, - std::string odom_topic = "odom"); + const std::string & odom_topic = "odom"); inline geometry_msgs::msg::Twist getTwist() {return vel_smooth_.twist;} inline geometry_msgs::msg::TwistStamped getTwistStamped() {return vel_smooth_;} @@ -59,8 +59,6 @@ class OdomSmoother void odomCallback(nav_msgs::msg::Odometry::SharedPtr msg); void updateState(); - rclcpp::Node::SharedPtr node_; - rclcpp::Subscription::SharedPtr odom_sub_; nav_msgs::msg::Odometry odom_cumulate_; geometry_msgs::msg::TwistStamped vel_smooth_; diff --git a/nav2_util/src/lifecycle_node.cpp b/nav2_util/src/lifecycle_node.cpp index c031e41dbb8..889ecaa61fb 100644 --- a/nav2_util/src/lifecycle_node.cpp +++ b/nav2_util/src/lifecycle_node.cpp @@ -69,6 +69,7 @@ LifecycleNode::LifecycleNode( LifecycleNode::~LifecycleNode() { + RCLCPP_INFO(get_logger(), "Destroying"); // In case this lifecycle node wasn't properly shut down, do it here if (get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) diff --git a/nav2_util/src/odometry_utils.cpp b/nav2_util/src/odometry_utils.cpp index f866bd92444..494b00e86c6 100644 --- a/nav2_util/src/odometry_utils.cpp +++ b/nav2_util/src/odometry_utils.cpp @@ -24,13 +24,13 @@ namespace nav2_util { OdomSmoother::OdomSmoother( - rclcpp::Node::SharedPtr nh, + const rclcpp::Node::WeakPtr & parent, double filter_duration, - std::string odom_topic) -: node_(nh), - odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration)) + const std::string & odom_topic) +: odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration)) { - odom_sub_ = nh->create_subscription( + auto node = parent.lock(); + odom_sub_ = node->create_subscription( odom_topic, rclcpp::SystemDefaultsQoS(), std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1)); diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index 13a998023bc..ab121b52878 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -35,7 +35,6 @@ WaypointFollower::WaypointFollower() WaypointFollower::~WaypointFollower() { - RCLCPP_INFO(get_logger(), "Destroying"); } nav2_util::CallbackReturn