Skip to content

Commit 3e4a7a3

Browse files
Use declare_or_get_param API (#5372)
* Rebase Signed-off-by: ElSayed ElSheikh <elsayed.elsheikh97@gmail.com> * Fix Signed-off-by: ElSayed ElSheikh <elsayed.elsheikh97@gmail.com> * Feedback Signed-off-by: ElSayed ElSheikh <elsayed.elsheikh97@gmail.com> --------- Signed-off-by: ElSayed ElSheikh <elsayed.elsheikh97@gmail.com>
1 parent 1dc2b58 commit 3e4a7a3

File tree

3 files changed

+42
-91
lines changed

3 files changed

+42
-91
lines changed

nav2_bt_navigator/src/bt_navigator.cpp

Lines changed: 8 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -38,19 +38,6 @@ BtNavigator::BtNavigator(rclcpp::NodeOptions options)
3838
class_loader_("nav2_core", "nav2_core::NavigatorBase")
3939
{
4040
RCLCPP_INFO(get_logger(), "Creating");
41-
42-
declare_parameter_if_not_declared(
43-
this, "plugin_lib_names", rclcpp::ParameterValue(std::vector<std::string>{}));
44-
declare_parameter_if_not_declared(
45-
this, "transform_tolerance", rclcpp::ParameterValue(0.1));
46-
declare_parameter_if_not_declared(
47-
this, "global_frame", rclcpp::ParameterValue(std::string("map")));
48-
declare_parameter_if_not_declared(
49-
this, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
50-
declare_parameter_if_not_declared(
51-
this, "odom_topic", rclcpp::ParameterValue(std::string("odom")));
52-
declare_parameter_if_not_declared(
53-
this, "filter_duration", rclcpp::ParameterValue(0.3));
5441
}
5542

5643
BtNavigator::~BtNavigator()
@@ -69,17 +56,18 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
6956
tf_->setUsingDedicatedThread(true);
7057
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
7158

72-
global_frame_ = get_parameter("global_frame").as_string();
73-
robot_frame_ = get_parameter("robot_base_frame").as_string();
74-
transform_tolerance_ = get_parameter("transform_tolerance").as_double();
75-
odom_topic_ = get_parameter("odom_topic").as_string();
76-
filter_duration_ = get_parameter("filter_duration").as_double();
59+
global_frame_ = this->declare_or_get_parameter("global_frame", std::string("map"));
60+
robot_frame_ = this->declare_or_get_parameter("robot_base_frame", std::string("base_link"));
61+
transform_tolerance_ = this->declare_or_get_parameter("transform_tolerance", 0.1);
62+
odom_topic_ = this->declare_or_get_parameter("odom_topic", std::string("odom"));
63+
filter_duration_ = this->declare_or_get_parameter("filter_duration", 0.3);
7764

7865
// Libraries to pull plugins (BT Nodes) from
7966
std::vector<std::string> plugin_lib_names;
8067
plugin_lib_names = nav2_util::split(nav2::details::BT_BUILTIN_PLUGINS, ';');
8168

82-
auto user_defined_plugins = get_parameter("plugin_lib_names").as_string_array();
69+
auto user_defined_plugins =
70+
this->declare_or_get_parameter("plugin_lib_names", std::vector<std::string>{});
8371
// append user_defined_plugins to plugin_lib_names
8472
plugin_lib_names.insert(
8573
plugin_lib_names.end(), user_defined_plugins.begin(),
@@ -106,10 +94,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
10694
};
10795

10896
std::vector<std::string> navigator_ids;
109-
declare_parameter_if_not_declared(
110-
node, "navigators",
111-
rclcpp::ParameterValue(default_navigator_ids));
112-
get_parameter("navigators", navigator_ids);
97+
navigator_ids = this->declare_or_get_parameter("navigators", default_navigator_ids);
11398
if (navigator_ids == default_navigator_ids) {
11499
for (size_t i = 0; i < default_navigator_ids.size(); ++i) {
115100
declare_parameter_if_not_declared(

nav2_bt_navigator/src/navigators/navigate_through_poses.cpp

Lines changed: 18 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -30,39 +30,25 @@ NavigateThroughPosesNavigator::configure(
3030
start_time_ = rclcpp::Time(0);
3131
auto node = parent_node.lock();
3232

33-
if (!node->has_parameter("goals_blackboard_id")) {
34-
node->declare_parameter("goals_blackboard_id", std::string("goals"));
35-
}
36-
37-
goals_blackboard_id_ = node->get_parameter("goals_blackboard_id").as_string();
38-
39-
if (!node->has_parameter("path_blackboard_id")) {
40-
node->declare_parameter("path_blackboard_id", std::string("path"));
41-
}
42-
43-
path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();
44-
45-
if (!node->has_parameter("waypoint_statuses_blackboard_id")) {
46-
node->declare_parameter("waypoint_statuses_blackboard_id", std::string("waypoint_statuses"));
47-
}
48-
33+
goals_blackboard_id_ =
34+
node->declare_or_get_parameter("goals_blackboard_id", std::string("goals"));
35+
path_blackboard_id_ =
36+
node->declare_or_get_parameter("path_blackboard_id", std::string("path"));
4937
waypoint_statuses_blackboard_id_ =
50-
node->get_parameter("waypoint_statuses_blackboard_id").as_string();
38+
node->declare_or_get_parameter("waypoint_statuses_blackboard_id",
39+
std::string("waypoint_statuses"));
5140

5241
// Odometry smoother object for getting current speed
5342
odom_smoother_ = odom_smoother;
5443

55-
if (!node->has_parameter(getName() + ".enable_groot_monitoring")) {
56-
node->declare_parameter(getName() + ".enable_groot_monitoring", false);
57-
}
58-
59-
if (!node->has_parameter(getName() + ".groot_server_port")) {
60-
node->declare_parameter(getName() + ".groot_server_port", 1669);
61-
}
44+
bool enable_groot_monitoring =
45+
node->declare_or_get_parameter(getName() + ".enable_groot_monitoring", false);
46+
int groot_server_port =
47+
node->declare_or_get_parameter(getName() + ".groot_server_port", 1669);
6248

6349
bt_action_server_->setGrootMonitoring(
64-
node->get_parameter(getName() + ".enable_groot_monitoring").as_bool(),
65-
node->get_parameter(getName() + ".groot_server_port").as_int());
50+
enable_groot_monitoring,
51+
groot_server_port);
6652

6753
return true;
6854
}
@@ -71,19 +57,14 @@ std::string
7157
NavigateThroughPosesNavigator::getDefaultBTFilepath(
7258
nav2::LifecycleNode::WeakPtr parent_node)
7359
{
74-
std::string default_bt_xml_filename;
7560
auto node = parent_node.lock();
61+
std::string pkg_share_dir =
62+
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
7663

77-
if (!node->has_parameter("default_nav_through_poses_bt_xml")) {
78-
std::string pkg_share_dir =
79-
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
80-
node->declare_parameter<std::string>(
81-
"default_nav_through_poses_bt_xml",
82-
pkg_share_dir +
83-
"/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
84-
}
85-
86-
node->get_parameter("default_nav_through_poses_bt_xml", default_bt_xml_filename);
64+
auto default_bt_xml_filename = node->declare_or_get_parameter(
65+
"default_nav_through_poses_bt_xml",
66+
pkg_share_dir +
67+
"/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
8768

8869
return default_bt_xml_filename;
8970
}

nav2_bt_navigator/src/navigators/navigate_to_pose.cpp

Lines changed: 16 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -29,17 +29,10 @@ NavigateToPoseNavigator::configure(
2929
start_time_ = rclcpp::Time(0);
3030
auto node = parent_node.lock();
3131

32-
if (!node->has_parameter("goal_blackboard_id")) {
33-
node->declare_parameter("goal_blackboard_id", std::string("goal"));
34-
}
35-
36-
goal_blackboard_id_ = node->get_parameter("goal_blackboard_id").as_string();
37-
38-
if (!node->has_parameter("path_blackboard_id")) {
39-
node->declare_parameter("path_blackboard_id", std::string("path"));
40-
}
41-
42-
path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();
32+
goal_blackboard_id_ =
33+
node->declare_or_get_parameter("goal_blackboard_id", std::string("goal"));
34+
path_blackboard_id_ =
35+
node->declare_or_get_parameter("path_blackboard_id", std::string("path"));
4336

4437
// Odometry smoother object for getting current speed
4538
odom_smoother_ = odom_smoother;
@@ -50,17 +43,14 @@ NavigateToPoseNavigator::configure(
5043
"goal_pose",
5144
std::bind(&NavigateToPoseNavigator::onGoalPoseReceived, this, std::placeholders::_1));
5245

53-
if (!node->has_parameter(getName() + ".enable_groot_monitoring")) {
54-
node->declare_parameter(getName() + ".enable_groot_monitoring", false);
55-
}
56-
57-
if (!node->has_parameter(getName() + ".groot_server_port")) {
58-
node->declare_parameter(getName() + ".groot_server_port", 1667);
59-
}
46+
bool enable_groot_monitoring =
47+
node->declare_or_get_parameter(getName() + ".enable_groot_monitoring", false);
48+
int groot_server_port =
49+
node->declare_or_get_parameter(getName() + ".groot_server_port", 1669);
6050

6151
bt_action_server_->setGrootMonitoring(
62-
node->get_parameter(getName() + ".enable_groot_monitoring").as_bool(),
63-
node->get_parameter(getName() + ".groot_server_port").as_int());
52+
enable_groot_monitoring,
53+
groot_server_port);
6454

6555
return true;
6656
}
@@ -69,19 +59,14 @@ std::string
6959
NavigateToPoseNavigator::getDefaultBTFilepath(
7060
nav2::LifecycleNode::WeakPtr parent_node)
7161
{
72-
std::string default_bt_xml_filename;
7362
auto node = parent_node.lock();
63+
std::string pkg_share_dir =
64+
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
7465

75-
if (!node->has_parameter("default_nav_to_pose_bt_xml")) {
76-
std::string pkg_share_dir =
77-
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
78-
node->declare_parameter<std::string>(
79-
"default_nav_to_pose_bt_xml",
80-
pkg_share_dir +
81-
"/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
82-
}
83-
84-
node->get_parameter("default_nav_to_pose_bt_xml", default_bt_xml_filename);
66+
auto default_bt_xml_filename = node->declare_or_get_parameter(
67+
"default_nav_to_pose_bt_xml",
68+
pkg_share_dir +
69+
"/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
8570

8671
return default_bt_xml_filename;
8772
}

0 commit comments

Comments
 (0)