Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

remove LifecycleNode's argument use_rclcpp_node #2993

Merged
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
2 changes: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace nav2_amcl
using nav2_util::geometry_utils::orientationAroundZAxis;

AmclNode::AmclNode(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("amcl", "", false, options)
: nav2_util::LifecycleNode("amcl", "", options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/src/behavior_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ namespace behavior_server
{

BehaviorServer::BehaviorServer(const rclcpp::NodeOptions & options)
: LifecycleNode("behavior_server", "", false, options),
: LifecycleNode("behavior_server", "", options),
plugin_loader_("nav2_core", "nav2_core::Behavior"),
default_ids_{"spin", "backup", "drive_on_heading", "wait"},
default_types_{"nav2_behaviors/Spin",
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ namespace nav2_bt_navigator
{

BtNavigator::BtNavigator(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("bt_navigator", "", false, options)
: nav2_util::LifecycleNode("bt_navigator", "", options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ namespace nav2_controller
{

ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("controller_server", "", false, options),
: nav2_util::LifecycleNode("controller_server", "", options),
progress_checker_loader_("nav2_core", "nav2_core::ProgressChecker"),
default_progress_checker_id_{"progress_checker"},
default_progress_checker_type_{"nav2_controller::SimpleProgressChecker"},
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,7 +311,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode
rclcpp::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;

// Dedicated callback group and executor for tf timer_interface, costmap plugins and filters
// Dedicated callback group and executor for tf timer_interface and message fillter
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
std::unique_ptr<nav2_util::NodeThread> executor_thread_;
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ Costmap2DROS::Costmap2DROS(
const std::string & name,
const std::string & parent_namespace,
const std::string & local_namespace)
: nav2_util::LifecycleNode(name, "", false,
: nav2_util::LifecycleNode(name, "",
// NodeOption arguments take precedence over the ones provided on the command line
// use this to make sure the node is placed on the provided namespace
// TODO(orduno) Pass a sub-node instead of creating a new node for better handling
Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/test/integration/inflation_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ void TestNode::initNode(std::vector<rclcpp::Parameter> parameters)
options.parameter_overrides(parameters);

node_ = std::make_shared<nav2_util::LifecycleNode>(
"inflation_test_node", "", false, options);
"inflation_test_node", "", options);

// Declare non-plugin specific costmap parameters
node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
{
public:
explicit TestCollisionChecker(std::string name)
: LifecycleNode(name, "", true),
: LifecycleNode(name),
global_frame_("map")
{
// Declare non-plugin specific costmap parameters
Expand All @@ -106,10 +106,13 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
on_configure(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Configuring");
callback_group_ = create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive, false);
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
rclcpp_node_->get_node_base_interface(),
rclcpp_node_->get_node_timers_interface());
get_node_base_interface(),
get_node_timers_interface(),
callback_group_);
tf_buffer_->setCreateTimerInterface(timer_interface);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
Expand All @@ -132,15 +135,18 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
layers_ = new nav2_costmap_2d::LayeredCostmap("map", false, false);
// Add Static Layer
std::shared_ptr<nav2_costmap_2d::StaticLayer> slayer = nullptr;
addStaticLayer(*layers_, *tf_buffer_, shared_from_this(), slayer);
addStaticLayer(*layers_, *tf_buffer_, shared_from_this(), slayer, callback_group_);

while (!slayer->isCurrent()) {
rclcpp::spin_some(this->get_node_base_interface());
}
// Add Inflation Layer
std::shared_ptr<nav2_costmap_2d::InflationLayer> ilayer = nullptr;
addInflationLayer(*layers_, *tf_buffer_, shared_from_this(), ilayer);
addInflationLayer(*layers_, *tf_buffer_, shared_from_this(), ilayer, callback_group_);

executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor_->add_callback_group(callback_group_, get_node_base_interface());
executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
return nav2_util::CallbackReturn::SUCCESS;
}

Expand All @@ -165,6 +171,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
delete layers_;
layers_ = nullptr;

executor_thread_.reset();
tf_buffer_.reset();

footprint_sub_.reset();
Expand Down Expand Up @@ -278,6 +285,10 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;

rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
std::unique_ptr<nav2_util::NodeThread> executor_thread_;

std::shared_ptr<DummyCostmapSubscriber> costmap_sub_;
std::shared_ptr<DummyFootprintSubscriber> footprint_sub_;
std::unique_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_;
Expand Down
20 changes: 12 additions & 8 deletions nav2_costmap_2d/test/testing_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,30 +71,33 @@ unsigned int countValues(
void addStaticLayer(
nav2_costmap_2d::LayeredCostmap & layers,
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
std::shared_ptr<nav2_costmap_2d::StaticLayer> & slayer)
std::shared_ptr<nav2_costmap_2d::StaticLayer> & slayer,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
slayer = std::make_shared<nav2_costmap_2d::StaticLayer>();
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(slayer));
slayer->initialize(&layers, "static", &tf, node, nullptr);
slayer->initialize(&layers, "static", &tf, node, callback_group);
}

void addObstacleLayer(
nav2_costmap_2d::LayeredCostmap & layers,
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> & olayer)
std::shared_ptr<nav2_costmap_2d::ObstacleLayer> & olayer,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
olayer = std::make_shared<nav2_costmap_2d::ObstacleLayer>();
olayer->initialize(&layers, "obstacles", &tf, node, nullptr);
olayer->initialize(&layers, "obstacles", &tf, node, callback_group);
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(olayer));
}

void addRangeLayer(
nav2_costmap_2d::LayeredCostmap & layers,
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
std::shared_ptr<nav2_costmap_2d::RangeSensorLayer> & rlayer)
std::shared_ptr<nav2_costmap_2d::RangeSensorLayer> & rlayer,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
rlayer = std::make_shared<nav2_costmap_2d::RangeSensorLayer>();
rlayer->initialize(&layers, "range", &tf, node, nullptr);
rlayer->initialize(&layers, "range", &tf, node, callback_group);
layers.addPlugin(std::shared_ptr<nav2_costmap_2d::Layer>(rlayer));
}

Expand Down Expand Up @@ -130,10 +133,11 @@ void addObservation(
void addInflationLayer(
nav2_costmap_2d::LayeredCostmap & layers,
tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node,
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer)
std::shared_ptr<nav2_costmap_2d::InflationLayer> & ilayer,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)
{
ilayer = std::make_shared<nav2_costmap_2d::InflationLayer>();
ilayer->initialize(&layers, "inflation", &tf, node, nullptr);
ilayer->initialize(&layers, "inflation", &tf, node, callback_group);
std::shared_ptr<nav2_costmap_2d::Layer> ipointer(ilayer);
layers.addPlugin(ipointer);
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ using namespace std::placeholders;
namespace nav2_map_server
{
MapSaver::MapSaver(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("map_saver", "", false, options)
: nav2_util::LifecycleNode("map_saver", "", options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/map_server/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace nav2_map_server
{

MapServer::MapServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("map_server", "", false, options)
: nav2_util::LifecycleNode("map_server", "", options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
2 changes: 1 addition & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ namespace nav2_planner
{

PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("planner_server", "", false, options),
: nav2_util::LifecycleNode("planner_server", "", options),
gp_loader_("nav2_core", "nav2_core::GlobalPlanner"),
default_ids_{"GridBased"},
default_types_{"nav2_navfn_planner/NavfnPlanner"},
Expand Down
2 changes: 1 addition & 1 deletion nav2_smoother/src/nav2_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ namespace nav2_smoother
{

SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
: LifecycleNode("smoother_server", "", false, options),
: LifecycleNode("smoother_server", "", options),
lp_loader_("nav2_core", "nav2_core::Smoother"),
default_ids_{"simple_smoother"},
default_types_{"nav2_smoother::SimpleSmoother"}
Expand Down
20 changes: 1 addition & 19 deletions nav2_util/include/nav2_util/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,9 @@ namespace nav2_util

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

// The following is a temporary wrapper for rclcpp_lifecycle::LifecycleNode. This class
// adds the optional creation of an rclcpp::Node that can be used by derived classes
// to interface to classes, such as MessageFilter and TransformListener, that don't yet
// support lifecycle nodes. Once we get the fixes into ROS2, this class will be removed.

/**
* @class nav2_util::LifecycleNode
* @brief A lifecycle node wrapper to enable common Nav2 needs such as background node threads
* and manipulating parameters
* @brief A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters
*/
class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
Expand All @@ -47,13 +41,11 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
* @brief A lifecycle node constructor
* @param node_name Name for the node
* @param namespace Namespace for the node, if any
* @param use_rclcpp_node Whether to create an internal client node
* @param options Node options
*/
LifecycleNode(
const std::string & node_name,
const std::string & ns = "",
bool use_rclcpp_node = false,
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
virtual ~LifecycleNode();

Expand Down Expand Up @@ -191,16 +183,6 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
*/
void printLifecycleNodeNotification();

// Whether or not to create a local rclcpp::Node which can be used for ROS2 classes that don't
// yet support lifecycle nodes
bool use_rclcpp_node_;

// The local node
rclcpp::Node::SharedPtr rclcpp_node_;

// When creating a local node, this class will launch a separate thread created to spin the node
std::unique_ptr<NodeThread> rclcpp_thread_;

// Connection to tell that server is still up
std::unique_ptr<bond::Bond> bond_{nullptr};
};
Expand Down
33 changes: 2 additions & 31 deletions nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,47 +23,18 @@
namespace nav2_util
{

// The nav2_util::LifecycleNode class is temporary until we get the
// required support for lifecycle nodes in MessageFilter, TransformListener,
// and TransforBroadcaster. We have submitted issues for these and will
// be submitting PRs to add the fixes:
//
// https://github.com/ros2/geometry2/issues/95
// https://github.com/ros2/geometry2/issues/94
// https://github.com/ros2/geometry2/issues/70
//
// Until then, this class can provide a normal ROS node that has a thread
// that processes the node's messages. If a derived class needs to interface
// to one of these classes - MessageFilter, etc. - that don't yet support
// lifecycle nodes, it can simply set the use_rclcpp_node flag in the
// constructor and then provide the rclcpp_node_ to the helper classes, like
// MessageFilter.
//

LifecycleNode::LifecycleNode(
const std::string & node_name,
const std::string & ns, bool use_rclcpp_node,
const std::string & ns,
const rclcpp::NodeOptions & options)
: rclcpp_lifecycle::LifecycleNode(node_name, ns, options),
use_rclcpp_node_(use_rclcpp_node)
: rclcpp_lifecycle::LifecycleNode(node_name, ns, options)
{
// server side never times out from lifecycle manager
this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true);
this->set_parameter(
rclcpp::Parameter(
bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true));

if (use_rclcpp_node_) {
std::vector<std::string> new_args = options.arguments();
new_args.push_back("--ros-args");
new_args.push_back("-r");
new_args.push_back(std::string("__node:=") + this->get_name() + "_rclcpp_node");
new_args.push_back("--");
rclcpp_node_ = std::make_shared<rclcpp::Node>(
"_", ns, rclcpp::NodeOptions(options).arguments(new_args));
rclcpp_thread_ = std::make_unique<NodeThread>(rclcpp_node_);
}

printLifecycleNodeNotification();
}

Expand Down
9 changes: 3 additions & 6 deletions nav2_util/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,19 +33,16 @@ RclCppFixture g_rclcppfixture;
TEST(LifecycleNode, RclcppNodeExitsCleanly)
{
// Make sure the node exits cleanly when using an rclcpp_node and associated thread
auto node1 = std::make_shared<nav2_util::LifecycleNode>("test_node", "", true);
auto node1 = std::make_shared<nav2_util::LifecycleNode>("test_node", "");
std::this_thread::sleep_for(std::chrono::seconds(1));
SUCCEED();
}

TEST(LifecycleNode, MultipleRclcppNodesExitCleanly)
{
// Try a couple nodes w/ rclcpp_node and threads
auto node1 = std::make_shared<nav2_util::LifecycleNode>("test_node1", "", true);
auto node2 = std::make_shared<nav2_util::LifecycleNode>("test_node2", "", true);

// Another one without rclcpp_node and on the stack
nav2_util::LifecycleNode node3("test_node3", "", false);
auto node1 = std::make_shared<nav2_util::LifecycleNode>("test_node1", "");
auto node2 = std::make_shared<nav2_util::LifecycleNode>("test_node2", "");

std::this_thread::sleep_for(std::chrono::seconds(1));
SUCCEED();
Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;

WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("waypoint_follower", "", false, options),
: nav2_util::LifecycleNode("waypoint_follower", "", options),
waypoint_task_executor_loader_("nav2_waypoint_follower",
"nav2_core::WaypointTaskExecutor")
{
Expand Down