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
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ BtActionServer<ActionT>::BtActionServer(
clock_ = node->get_clock();

// Declare this node's parameters
node->declare_parameter("default_bt_xml_filename");
node->declare_parameter("default_bt_xml_filename", rclcpp::PARAMETER_STRING);
node->declare_parameter("enable_groot_monitoring", true);
node->declare_parameter("groot_zmq_publisher_port", 1666);
node->declare_parameter("groot_zmq_server_port", 1667);
Expand Down
3 changes: 2 additions & 1 deletion nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,8 @@ class Layer // TODO(mjeronimo): public nav2_util::LifecycleHelperInterface
const std::string & param_name,
const rclcpp::ParameterValue & value);
void declareParameter(
const std::string & param_name);
const std::string & param_name,
const rclcpp::ParameterType & param_type);
bool hasParameter(const std::string & param_name);
std::string getFullName(const std::string & param_name);

Expand Down
24 changes: 12 additions & 12 deletions nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,22 +60,22 @@ void CostmapFilter::onInitialize()
throw std::runtime_error{"Failed to lock node"};
}

// Declare common for all costmap filters parameters
declareParameter("enabled", rclcpp::ParameterValue(true));
declareParameter("filter_info_topic");
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.1));

// Get parameters
node->get_parameter(name_ + "." + "enabled", enabled_);
try {
// Declare common for all costmap filters parameters
declareParameter("enabled", rclcpp::ParameterValue(true));
declareParameter("filter_info_topic", rclcpp::PARAMETER_STRING);
Comment thread
SteveMacenski marked this conversation as resolved.
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.1));

// Get parameters
node->get_parameter(name_ + "." + "enabled", enabled_);
filter_info_topic_ = node->get_parameter(name_ + "." + "filter_info_topic").as_string();
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
RCLCPP_ERROR(logger_, "filter_info_topic parameter is not set");
double transform_tolerance;
node->get_parameter(name_ + "." + "transform_tolerance", transform_tolerance);
transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
} catch (const std::exception & ex) {
RCLCPP_ERROR(logger_, "Parameter problem: %s", ex.what());
throw ex;
}
double transform_tolerance;
node->get_parameter(name_ + "." + "transform_tolerance", transform_tolerance);
transform_tolerance_ = tf2::durationFromSec(transform_tolerance);
}

void CostmapFilter::activate()
Expand Down
5 changes: 3 additions & 2 deletions nav2_costmap_2d/src/layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,15 +91,16 @@ Layer::declareParameter(

void
Layer::declareParameter(
const std::string & param_name)
const std::string & param_name,
const rclcpp::ParameterType & param_type)
{
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
local_params_.insert(param_name);
nav2_util::declare_parameter_if_not_declared(
node, getFullName(param_name));
node, getFullName(param_name), param_type);
}

bool
Expand Down
31 changes: 5 additions & 26 deletions nav2_costmap_2d/test/unit/declare_parameter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class LayerWrapper : public nav2_costmap_2d::Layer
bool isClearable() {return false;}
};

TEST(DeclareParameter, useValidParameter2Args)
TEST(DeclareParameter, useValidParameter)
{
LayerWrapper layer;
nav2_util::LifecycleNode::SharedPtr node =
Expand All @@ -55,7 +55,7 @@ TEST(DeclareParameter, useValidParameter2Args)
}
}

TEST(DeclareParameter, useValidParameter1Arg)
TEST(DeclareParameter, useInvalidParameter)
{
LayerWrapper layer;
nav2_util::LifecycleNode::SharedPtr node =
Expand All @@ -65,31 +65,10 @@ TEST(DeclareParameter, useValidParameter1Arg)

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

layer.declareParameter("test2");
try {
node->set_parameter(rclcpp::Parameter("test_layer.test2", "test_val2"));
std::string val = node->get_parameter("test_layer.test2").as_string();
EXPECT_EQ(val, "test_val2");
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
FAIL() << "test_layer.test2 parameter is not set";
}
}

TEST(DeclareParameter, useInvalidParameter1Arg)
{
LayerWrapper layer;
nav2_util::LifecycleNode::SharedPtr node =
std::make_shared<nav2_util::LifecycleNode>("test_node");
tf2_ros::Buffer tf(node->get_clock());
nav2_costmap_2d::LayeredCostmap layers("frame", false, false);

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

layer.declareParameter("test3");
try {
std::string val = node->get_parameter("test_layer.test3").as_string();
FAIL() << "Incorrectly handling test_layer.test3 parameters which was not set";
} catch (rclcpp::exceptions::ParameterNotDeclaredException & ex) {
layer.declareParameter("test2", rclcpp::PARAMETER_STRING);
FAIL() << "Incorrectly handling test_layer.test2 parameter which was not set";
} catch (rclcpp::exceptions::NoParameterOverrideProvided & ex) {
SUCCEED();
}
}
8 changes: 6 additions & 2 deletions nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,12 @@ void DWBLocalPlanner::configure(
costmap_ros_ = costmap_ros;
tf_ = tf;
dwb_plugin_name_ = name;
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".critics");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".default_critic_namespaces");
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".critics",
rclcpp::PARAMETER_STRING_ARRAY);
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".default_critic_namespaces",
rclcpp::ParameterValue(std::vector<std::string>()));
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".prune_plan",
rclcpp::ParameterValue(true));
Expand Down
18 changes: 14 additions & 4 deletions nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,20 @@ void LimitedAccelGenerator::initialize(
plugin_name_ = plugin_name;
StandardTrajectoryGenerator::initialize(nh, plugin_name_);

nav2_util::declare_parameter_if_not_declared(nh, plugin_name + ".sim_period");

if (nh->get_parameter(plugin_name + ".sim_period", acceleration_time_)) {
} else {
try {
nav2_util::declare_parameter_if_not_declared(
nh, plugin_name + ".sim_period", rclcpp::PARAMETER_DOUBLE);
if (!nh->get_parameter(plugin_name + ".sim_period", acceleration_time_)) {
// This actually should never appear, since declare_parameter_if_not_declared()
// completed w/o exceptions guarantee that static parameter will be initialized
// with some value. However for reliability we should also process the case
// when get_parameter() will return a failure for some other reasons.
throw std::runtime_error("Failed to get 'sim_period' value");
}
} catch (std::exception &) {
RCLCPP_WARN(
rclcpp::get_logger("LimitedAccelGenerator"),
"'sim_period' parameter is not set for %s", plugin_name.c_str());
double controller_frequency = nav_2d_utils::searchAndGetParam(
nh, "controller_frequency", 20.0);
if (controller_frequency > 0) {
Expand Down
2 changes: 1 addition & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ LifecycleManager::LifecycleManager()

// The list of names is parameterized, allowing this module to be used with a different set
// of nodes
declare_parameter("node_names");
declare_parameter("node_names", rclcpp::PARAMETER_STRING_ARRAY);
declare_parameter("autostart", rclcpp::ParameterValue(false));
declare_parameter("bond_timeout", 4.0);

Expand Down
2 changes: 1 addition & 1 deletion nav2_map_server/src/map_server/map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ MapServer::MapServer()
RCLCPP_INFO(get_logger(), "Creating");

// Declare the node parameters
declare_parameter("yaml_filename");
declare_parameter("yaml_filename", rclcpp::PARAMETER_STRING);
declare_parameter("topic_name", "map");
declare_parameter("frame_id", "map");
}
Expand Down
54 changes: 51 additions & 3 deletions nav2_util/include/nav2_util/node_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,11 +80,20 @@ std::string time_to_string(size_t len);
rclcpp::NodeOptions
get_node_options_default(bool allow_undeclared = true, bool declare_initial_params = true);

/// Declares static ROS2 parameter and sets it to a given value if it was not already declared
/* Declares static ROS2 parameter and sets it to a given value
* if it was not already declared.
*
* \param[in] node A node in which given parameter to be declared
* \param[in] param_name The name of parameter
* \param[in] default_value Parameter value to initialize with
* \param[in] parameter_descriptor Parameter descriptor (optional)
*/
template<typename NodeT>
void declare_parameter_if_not_declared(
NodeT node,
const std::string & param_name,
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor())
{
Expand All @@ -93,15 +102,54 @@ 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
* \param[in] default_value Parameter value to initialize with
* \param[in] parameter_descriptor Parameter descriptor (optional)
*/
template<typename NodeT>
void declare_parameter_if_not_declared(
NodeT node,
const std::string & param_name,
const rclcpp::ParameterType & param_type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor())
{
if (!node->has_parameter(param_name)) {
node->declare_parameter(param_name, param_type, parameter_descriptor);
}
}

/// Gets the type of plugin for the selected node and its plugin
/**
* Gets the type of plugin for the selected node and its plugin.
* Actually seeks for the value of "<plugin_name>.plugin" parameter.
*
* \param[in] node Selected node
* \param[in] plugin_name The name of plugin the type of which is being searched for
* \return A string containing the type of plugin (the value of "<plugin_name>.plugin" parameter)
*/
template<typename NodeT>
std::string get_plugin_type_param(
NodeT node,
const std::string & plugin_name)
{
declare_parameter_if_not_declared(node, plugin_name + ".plugin");
try {
declare_parameter_if_not_declared(node, plugin_name + ".plugin", rclcpp::PARAMETER_STRING);
} catch (rclcpp::exceptions::NoParameterOverrideProvided & 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(), "'plugin' param not defined for %s", plugin_name.c_str());
RCLCPP_FATAL(
node->get_logger(), "Can not get 'plugin' param value for %s", plugin_name.c_str());
exit(-1);
}
return plugin_type;
Expand Down
1 change: 0 additions & 1 deletion nav2_util/test/test_dump_params/dump_params_md.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
|Parameter|Default Value|
|---|---|
|use_sim_time|False|
|param_not_set|NOT_SET|
|param_bool|True|
|param_int|1234|
|param_double|3.14|
Expand Down
1 change: 0 additions & 1 deletion nav2_util/test/test_dump_params/dump_params_md_verbose.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
|Parameter|Default Value|Range|Description|Additional Constraints|Read-Only|
|---|---|---|---|---|---|
|use_sim_time|False|N/A|||False|
|param_not_set|NOT_SET|N/A|not set||False|
|param_bool|True|N/A|boolean||True|
|param_int|1234|-1000;10000;2||||False|
|param_double|3.14|N/A|||False|
Expand Down
2 changes: 0 additions & 2 deletions nav2_util/test/test_dump_params/dump_params_multiple.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
test_dump_params:
ros__parameters:
use_sim_time: False
param_not_set: NOT_SET
param_bool: True
param_int: 1234
param_double: 3.14
Expand All @@ -15,7 +14,6 @@ test_dump_params:
test_dump_params_copy:
ros__parameters:
use_sim_time: False
param_not_set: NOT_SET
param_bool: True
param_int: 1234
param_double: 3.14
Expand Down
1 change: 0 additions & 1 deletion nav2_util/test/test_dump_params/dump_params_yaml.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
test_dump_params:
ros__parameters:
use_sim_time: False
param_not_set: NOT_SET
param_bool: True
param_int: 1234
param_double: 3.14
Expand Down
6 changes: 0 additions & 6 deletions nav2_util/test/test_dump_params/dump_params_yaml_verbose.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,6 @@ test_dump_params:
# Additional constraints:
# Read-only: False

param_not_set: NOT_SET
# Range: N/A
# Description: not set
# Additional constraints:
# Read-only: False

param_bool: True
# Range: N/A
# Description: boolean
Expand Down
2 changes: 0 additions & 2 deletions nav2_util/test/test_dump_params/test_dump_params_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,6 @@ class TestDumpParamsNode(Node):

def __init__(self, name):
Node.__init__(self, name)
self.declare_parameter('param_not_set',
descriptor=ParameterDescriptor(description='not set'))
self.declare_parameter('param_bool',
True,
ParameterDescriptor(description='boolean', read_only=True))
Expand Down