Skip to content

Commit

Permalink
Add argument node options (#2522)
Browse files Browse the repository at this point in the history
* add argument node_options

Signed-off-by: zhenpeng ge <[email protected]>

* change node's name

Signed-off-by: zhenpeng ge <[email protected]>

* fix code style

Signed-off-by: zhenpeng ge <[email protected]>
  • Loading branch information
gezp authored Aug 19, 2021
1 parent cc8d276 commit 4e45ad3
Show file tree
Hide file tree
Showing 18 changed files with 36 additions and 27 deletions.
3 changes: 2 additions & 1 deletion nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,9 @@ class AmclNode : public nav2_util::LifecycleNode
public:
/*
* @brief AMCL constructor
* @param options Additional options to control creation of the node.
*/
AmclNode();
explicit AmclNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/*
* @brief AMCL destructor
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ namespace nav2_amcl
{
using nav2_util::geometry_utils::orientationAroundZAxis;

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

Expand Down
3 changes: 2 additions & 1 deletion nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@ class BtNavigator : public nav2_util::LifecycleNode
public:
/**
* @brief A constructor for nav2_bt_navigator::BtNavigator class
* @param options Additional options to control creation of the node.
*/
BtNavigator();
explicit BtNavigator(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/**
* @brief A destructor for nav2_bt_navigator::BtNavigator class
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@
namespace nav2_bt_navigator
{

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

Expand Down
3 changes: 2 additions & 1 deletion nav2_controller/include/nav2_controller/nav2_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,9 @@ class ControllerServer : public nav2_util::LifecycleNode

/**
* @brief Constructor for nav2_controller::ControllerServer
* @param options Additional options to control creation of the node.
*/
ControllerServer();
explicit ControllerServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/**
* @brief Destructor for nav2_controller::ControllerServer
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ using namespace std::chrono_literals;
namespace nav2_controller
{

ControllerServer::ControllerServer()
: nav2_util::LifecycleNode("controller_server", ""),
ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("controller_server", "", false, options),
progress_checker_loader_("nav2_core", "nav2_core::ProgressChecker"),
default_progress_checker_id_{"progress_checker"},
default_progress_checker_type_{"nav2_controller::SimpleProgressChecker"},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,9 @@ class LifecycleManager : public rclcpp::Node
public:
/**
* @brief A constructor for nav2_lifecycle_manager::LifecycleManager
* @param options Additional options to control creation of the node.
*/
LifecycleManager();
explicit LifecycleManager(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/**
* @brief A destructor for nav2_lifecycle_manager::LifecycleManager
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ using nav2_util::LifecycleServiceClient;
namespace nav2_lifecycle_manager
{

LifecycleManager::LifecycleManager()
: Node("lifecycle_manager")
LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
: Node("lifecycle_manager", options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
3 changes: 2 additions & 1 deletion nav2_map_server/include/nav2_map_server/map_saver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,9 @@ class MapSaver : public nav2_util::LifecycleNode
public:
/**
* @brief Constructor for the nav2_map_server::MapSaver
* @param options Additional options to control creation of the node.
*/
MapSaver();
explicit MapSaver(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

/**
* @brief Destructor for the nav2_map_server::MapServer
Expand Down
3 changes: 2 additions & 1 deletion nav2_map_server/include/nav2_map_server/map_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@ class MapServer : public nav2_util::LifecycleNode
public:
/**
* @brief A constructor for nav2_map_server::MapServer
* @param options Additional options to control creation of the node.
*/
MapServer();
explicit MapServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

/**
* @brief A Destructor for nav2_map_server::MapServer
Expand Down
4 changes: 2 additions & 2 deletions nav2_map_server/src/map_saver/map_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@ using namespace std::placeholders;

namespace nav2_map_server
{
MapSaver::MapSaver()
: nav2_util::LifecycleNode("map_saver", "")
MapSaver::MapSaver(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("map_saver", "", false, options)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down
4 changes: 2 additions & 2 deletions nav2_map_server/src/map_server/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,8 @@ using namespace std::placeholders;
namespace nav2_map_server
{

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

Expand Down
3 changes: 2 additions & 1 deletion nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,9 @@ class PlannerServer : public nav2_util::LifecycleNode
public:
/**
* @brief A constructor for nav2_planner::PlannerServer
* @param options Additional options to control creation of the node.
*/
PlannerServer();
explicit PlannerServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/**
* @brief A destructor for nav2_planner::PlannerServer
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ using namespace std::chrono_literals;
namespace nav2_planner
{

PlannerServer::PlannerServer()
: nav2_util::LifecycleNode("nav2_planner", ""),
PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("planner_server", "", false, options),
gp_loader_("nav2_core", "nav2_core::GlobalPlanner"),
default_ids_{"GridBased"},
default_types_{"nav2_navfn_planner/NavfnPlanner"},
Expand Down
3 changes: 2 additions & 1 deletion nav2_recoveries/include/nav2_recoveries/recovery_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@ class RecoveryServer : public nav2_util::LifecycleNode
public:
/**
* @brief A constructor for recovery_server::RecoveryServer
* @param options Additional options to control creation of the node.
*/
RecoveryServer();
explicit RecoveryServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~RecoveryServer();

/**
Expand Down
4 changes: 2 additions & 2 deletions nav2_recoveries/src/recovery_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@
namespace recovery_server
{

RecoveryServer::RecoveryServer()
: LifecycleNode("recoveries_server", "", true),
RecoveryServer::RecoveryServer(const rclcpp::NodeOptions & options)
: LifecycleNode("recoveries_server", "", false, options),
plugin_loader_("nav2_core", "nav2_core::Recovery"),
default_ids_{"spin", "backup", "wait"},
default_types_{"nav2_recoveries/Spin", "nav2_recoveries/BackUp", "nav2_recoveries/Wait"}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,9 @@ class WaypointFollower : public nav2_util::LifecycleNode

/**
* @brief A constructor for nav2_waypoint_follower::WaypointFollower class
* @param options Additional options to control creation of the node.
*/
WaypointFollower();
explicit WaypointFollower(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
/**
* @brief A destructor for nav2_waypoint_follower::WaypointFollower class
*/
Expand Down
4 changes: 2 additions & 2 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@
namespace nav2_waypoint_follower
{

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

0 comments on commit 4e45ad3

Please sign in to comment.