Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,6 @@ AmclNode::AmclNode()

AmclNode::~AmclNode()
{
RCLCPP_INFO(get_logger(), "Destroying");
}

nav2_util::CallbackReturn
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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")};
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it might be worth noting on these that the names won't actually be used (right? cause these get overwritten in the constructor once we have the SharedPtr?). I could see someone getting confused if they expect the logger to have this name but instead it has the name of whatever the node has been named at runtime.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the idea here was to default the logger object to a reasonable name in case the logger object isn't overridden by a user since a lot of the places that use the logger object are plugin interfaces that could be further implemented by an external user.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would agree with @mikeferguson, if we were going to set them, then I think this is the way to do it, but I think we should ensure that they're always set properly from the node. For the case of new plugins, they'll be given a new WeakPtr for them to own and they'll need to store their own logger_ to use. For everything in the codebase itself, we should ensure that its always properly set so that it respects remaps.

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a nice safety mechanism for the specific nodes where that mistake may be possible (costmap_2d comes to mind). I'm not sure that is possible in other places like this instance. We "own" BT navigator's node and logger object, there's no plugin coming along to not properly initialize it

rclcpp::Publisher<nav2_msgs::msg::BehaviorTreeLog>::SharedPtr log_pub_;
std::vector<nav2_msgs::msg::BehaviorTreeStatusChange> event_log_;
};
Expand Down
6 changes: 2 additions & 4 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@

#include <fstream>
#include <memory>
#include <streambuf>
#include <string>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -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",
Expand All @@ -72,7 +71,6 @@ BtNavigator::BtNavigator()

BtNavigator::~BtNavigator()
{
RCLCPP_INFO(get_logger(), "Destroying");
}

nav2_util::CallbackReturn
Expand Down Expand Up @@ -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(
Expand Down
15 changes: 9 additions & 6 deletions nav2_bt_navigator/src/ros_topic_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<nav2_msgs::msg::BehaviorTreeLog>(
auto node = ros_node.lock();
clock_ = node->get_clock();
logger_ = node->get_logger();
log_pub_ = node->create_publisher<nav2_msgs::msg::BehaviorTreeLog>(
"behavior_tree_log",
rclcpp::QoS(10));
}
Expand All @@ -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<double>(timestamp).count(),
node.name().c_str(),
toStr(prev_status, true).c_str(),
Expand All @@ -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<nav2_msgs::msg::BehaviorTreeLog>();
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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For all instances: I don't think its generally best practice to pass smart pointers by reference. Weak ptrs might be different, but I don't see any documentation about that. Why not have the weakptr be by value?

Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

From this comment: #1900 (comment) what you say makes sense to me, but the conventions around smart pointers are the opposite. We should discuss this and then resolve one way or another.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Passing shared_ptrs by reference makes sense (to avoid the overhead of incrementing and then decrementing the reference count). For a weak_ptr though, it doesn't have the same overhead - although the multiple copy/initialization argument does seem to make since for this use case.

const std::string & plugin_name) override;
void reset() override;
bool isGoalReached(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
16 changes: 9 additions & 7 deletions nav2_controller/plugins/simple_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
}
Expand Down
28 changes: 12 additions & 16 deletions nav2_controller/plugins/simple_progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand All @@ -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()
Expand All @@ -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(
Expand Down
14 changes: 8 additions & 6 deletions nav2_controller/plugins/stopped_goal_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
10 changes: 4 additions & 6 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,9 @@ ControllerServer::ControllerServer()

ControllerServer::~ControllerServer()
{
RCLCPP_INFO(get_logger(), "Destroying");
progress_checker_.reset();
goal_checker_.reset();
controllers_.clear();
}

nav2_util::CallbackReturn
Expand All @@ -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(
Expand Down Expand Up @@ -394,10 +395,7 @@ void ControllerServer::updateGlobalPath()
void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity)
{
auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>(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));
}
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/include/nav2_core/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::Buffer> &,
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> &) = 0;

Expand Down
2 changes: 1 addition & 1 deletion nav2_core/include/nav2_core/global_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0;

Expand Down
4 changes: 2 additions & 2 deletions nav2_core/include/nav2_core/goal_checker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
/**
Expand Down
4 changes: 2 additions & 2 deletions nav2_core/include/nav2_core/progress_checker.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/include/nav2_core/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::Buffer> tf,
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker) = 0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand All @@ -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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -130,7 +130,9 @@ class Costmap2DPublisher
const std::shared_ptr<nav2_msgs::srv::GetCostmap::Request> request,
const std::shared_ptr<nav2_msgs::srv::GetCostmap::Response> 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_;
Expand Down
Loading