Skip to content
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
5 changes: 3 additions & 2 deletions nav2_costmap_2d/test/unit/declare_parameter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,11 @@ TEST(DeclareParameter, useInvalidParameter)

layer.initialize(&layers, "test_layer", &tf, node, nullptr, nullptr);

layer.declareParameter("test2", rclcpp::PARAMETER_STRING);
try {
layer.declareParameter("test2", rclcpp::PARAMETER_STRING);
std::string val = node->get_parameter("test_layer.test2").as_string();
FAIL() << "Incorrectly handling test_layer.test2 parameter which was not set";
} catch (rclcpp::exceptions::NoParameterOverrideProvided & ex) {
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
SUCCEED();
}
}
20 changes: 9 additions & 11 deletions nav2_util/include/nav2_util/node_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,9 +104,6 @@ void declare_parameter_if_not_declared(

/// Declares static ROS2 parameter with given type if it was not already declared
/* Declares static ROS2 parameter with given type if it was not already declared.
* NOTE: The parameter should be set via input param-file
* or throught a command-line. Otherwise according to the RCLCPP API,
* NoParameterOverrideProvided exception will be thrown by declare_parameter().
*
* \param[in] node A node in which given parameter to be declared
* \param[in] param_type The type of parameter
Expand Down Expand Up @@ -140,18 +137,19 @@ std::string get_plugin_type_param(
NodeT node,
const std::string & plugin_name)
{
declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
std::string plugin_type;
try {
declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
} catch (rclcpp::exceptions::NoParameterOverrideProvided & ex) {
if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
RCLCPP_FATAL(
node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
exit(-1);
}
} catch (rclcpp::exceptions::ParameterUninitializedException & ex) {
RCLCPP_FATAL(node->get_logger(), "'plugin' param not defined for %s", plugin_name.c_str());
exit(-1);
}
std::string plugin_type;
if (!node->get_parameter(plugin_name + ".plugin", plugin_type)) {
RCLCPP_FATAL(
node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
exit(-1);
}

return plugin_type;
}

Expand Down