Skip to content

Commit e3c7707

Browse files
Migrate the parameter API usage in nav2_costmap_2d package to the new style.
Signed-off-by: Leander Stephen D'Souza <[email protected]>
1 parent d536d33 commit e3c7707

File tree

2 files changed

+23
-45
lines changed

2 files changed

+23
-45
lines changed

nav2_costmap_2d/plugins/plugin_container_layer.cpp

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -35,18 +35,11 @@ void PluginContainerLayer::onInitialize()
3535
throw std::runtime_error{"Failed to lock node"};
3636
}
3737

38-
nav2::declare_parameter_if_not_declared(node, name_ + "." + "enabled",
39-
rclcpp::ParameterValue(true));
40-
nav2::declare_parameter_if_not_declared(node, name_ + "." + "plugins",
41-
rclcpp::ParameterValue(std::vector<std::string>{}));
42-
nav2::declare_parameter_if_not_declared(node, name_ + "." + "combination_method",
43-
rclcpp::ParameterValue(1));
44-
45-
node->get_parameter(name_ + "." + "enabled", enabled_);
46-
node->get_parameter(name_ + "." + "plugins", plugin_names_);
47-
48-
int combination_method_param{};
49-
node->get_parameter(name_ + "." + "combination_method", combination_method_param);
38+
enabled_ = node->declare_or_get_parameter(name_ + "." + "enabled", true);
39+
plugin_names_ = node->declare_or_get_parameter(
40+
name_ + "." + "plugins", std::vector<std::string>{});
41+
int combination_method_param = node->declare_or_get_parameter(
42+
name_ + "." + "combination_method", 1);
5043
combination_method_ = combination_method_from_int(combination_method_param);
5144

5245
dyn_params_handler_ = node->add_on_set_parameters_callback(

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 18 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -108,32 +108,15 @@ void Costmap2DROS::init()
108108
{
109109
RCLCPP_INFO(get_logger(), "Creating Costmap");
110110

111-
declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
112-
declare_parameter("map_vis_z", rclcpp::ParameterValue(0.0));
113-
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
114-
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
115111
declare_parameter("global_frame", rclcpp::ParameterValue(std::string("map")));
116-
declare_parameter("height", rclcpp::ParameterValue(5));
117-
declare_parameter("width", rclcpp::ParameterValue(5));
118112
declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
119113
declare_parameter("observation_sources", rclcpp::ParameterValue(std::string("")));
120-
declare_parameter("origin_x", rclcpp::ParameterValue(0.0));
121-
declare_parameter("origin_y", rclcpp::ParameterValue(0.0));
122114
declare_parameter("plugins", rclcpp::ParameterValue(default_plugins_));
123-
declare_parameter("filters", rclcpp::ParameterValue(std::vector<std::string>()));
124-
declare_parameter("publish_frequency", rclcpp::ParameterValue(1.0));
125-
declare_parameter("resolution", rclcpp::ParameterValue(0.1));
126115
declare_parameter("robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
127116
declare_parameter("robot_radius", rclcpp::ParameterValue(0.1));
128-
declare_parameter("rolling_window", rclcpp::ParameterValue(false));
129-
declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
130-
declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.3));
131117
declare_parameter("initial_transform_timeout", rclcpp::ParameterValue(60.0));
132118
declare_parameter("trinary_costmap", rclcpp::ParameterValue(true));
133119
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
134-
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
135-
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
136-
declare_parameter("subscribe_to_stamped_footprint", rclcpp::ParameterValue(false));
137120
}
138121

139122
Costmap2DROS::~Costmap2DROS()
@@ -402,27 +385,29 @@ Costmap2DROS::getParameters()
402385
RCLCPP_DEBUG(get_logger(), " getParameters");
403386

404387
// Get all of the required parameters
405-
get_parameter("always_send_full_costmap", always_send_full_costmap_);
406-
get_parameter("map_vis_z", map_vis_z_);
407-
get_parameter("footprint", footprint_);
408-
get_parameter("footprint_padding", footprint_padding_);
388+
always_send_full_costmap_ = declare_or_get_parameter("always_send_full_costmap", false);
389+
map_vis_z_ = declare_or_get_parameter("map_vis_z", 0.0);
390+
footprint_ = declare_or_get_parameter("footprint", std::string("[]"));
391+
footprint_padding_ = declare_or_get_parameter("footprint_padding", 0.01f);
392+
map_height_meters_ = declare_or_get_parameter("height", 5);
393+
origin_x_ = declare_or_get_parameter("origin_x", 0.0);
394+
origin_y_ = declare_or_get_parameter("origin_y", 0.0);
395+
map_publish_frequency_ = declare_or_get_parameter("publish_frequency", 1.0);
396+
resolution_ = declare_or_get_parameter("resolution", 0.1);
397+
rolling_window_ = declare_or_get_parameter("rolling_window", false);
398+
track_unknown_space_ = declare_or_get_parameter("track_unknown_space", false);
399+
transform_tolerance_ = declare_or_get_parameter("transform_tolerance", 0.3);
400+
map_update_frequency_ = declare_or_get_parameter("update_frequency", 5.0);
401+
map_width_meters_ = declare_or_get_parameter("width", 5);
402+
filter_names_ = declare_or_get_parameter("filters", std::vector<std::string>());
403+
subscribe_to_stamped_footprint_ = declare_or_get_parameter(
404+
"subscribe_to_stamped_footprint", false);
405+
409406
get_parameter("global_frame", global_frame_);
410-
get_parameter("height", map_height_meters_);
411-
get_parameter("origin_x", origin_x_);
412-
get_parameter("origin_y", origin_y_);
413-
get_parameter("publish_frequency", map_publish_frequency_);
414-
get_parameter("resolution", resolution_);
415407
get_parameter("robot_base_frame", robot_base_frame_);
416408
get_parameter("robot_radius", robot_radius_);
417-
get_parameter("rolling_window", rolling_window_);
418-
get_parameter("track_unknown_space", track_unknown_space_);
419-
get_parameter("transform_tolerance", transform_tolerance_);
420409
get_parameter("initial_transform_timeout", initial_transform_timeout_);
421-
get_parameter("update_frequency", map_update_frequency_);
422-
get_parameter("width", map_width_meters_);
423410
get_parameter("plugins", plugin_names_);
424-
get_parameter("filters", filter_names_);
425-
get_parameter("subscribe_to_stamped_footprint", subscribe_to_stamped_footprint_);
426411

427412
auto node = shared_from_this();
428413

0 commit comments

Comments
 (0)