@@ -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
5643BtNavigator::~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 (
0 commit comments