Skip to content

Commit bfce96b

Browse files
committed
Declare parameters uninitialized (#1673)
* Declare parameters uninitialized Fixes #1649 Allow declaring parameters without an initial value or override. This was possible prior to Galactic, but was made impossible since we started enforcing the types of parameters in Galactic. Signed-off-by: Jacob Perron <[email protected]> * Remove assertion Signed-off-by: Jacob Perron <[email protected]> * Throw NoParameterOverrideProvided exception if accessed before initialized Signed-off-by: Jacob Perron <[email protected]> * Add test getting static parameter after it is set Signed-off-by: Jacob Perron <[email protected]> * Do not throw on access of uninitialized dynamically typed parameter Signed-off-by: Jacob Perron <[email protected]> * Rename exception type Signed-off-by: Jacob Perron <[email protected]> * Remove unused exception type Signed-off-by: Jacob Perron <[email protected]> * Uncrustify Signed-off-by: Jacob Perron <[email protected]>
1 parent e9313c3 commit bfce96b

File tree

3 files changed

+50
-20
lines changed

3 files changed

+50
-20
lines changed

rclcpp/include/rclcpp/exceptions/exceptions.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -282,17 +282,17 @@ class ParameterModifiedInCallbackException : public std::runtime_error
282282
using std::runtime_error::runtime_error;
283283
};
284284

285-
/// Thrown when a parameter override wasn't provided and one was required.
286-
class NoParameterOverrideProvided : public std::runtime_error
285+
/// Thrown when an uninitialized parameter is accessed.
286+
class ParameterUninitializedException : public std::runtime_error
287287
{
288288
public:
289289
/// Construct an instance.
290290
/**
291291
* \param[in] name the name of the parameter.
292292
* \param[in] message custom exception message.
293293
*/
294-
explicit NoParameterOverrideProvided(const std::string & name)
295-
: std::runtime_error("parameter '" + name + "' requires an user provided parameter override")
294+
explicit ParameterUninitializedException(const std::string & name)
295+
: std::runtime_error("parameter '" + name + "' is not initialized")
296296
{}
297297
};
298298

rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp

Lines changed: 27 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -349,6 +349,21 @@ __declare_parameter_common(
349349
initial_value = &overrides_it->second;
350350
}
351351

352+
// If there is no initial value, then skip initialization
353+
if (initial_value->get_type() == rclcpp::PARAMETER_NOT_SET) {
354+
// Add declared parameters to storage (without a value)
355+
parameter_infos[name].descriptor.name = name;
356+
if (parameter_descriptor.dynamic_typing) {
357+
parameter_infos[name].descriptor.type = rclcpp::PARAMETER_NOT_SET;
358+
} else {
359+
parameter_infos[name].descriptor.type = parameter_descriptor.type;
360+
}
361+
parameters_out[name] = parameter_infos.at(name);
362+
rcl_interfaces::msg::SetParametersResult result;
363+
result.successful = true;
364+
return result;
365+
}
366+
352367
// Check with the user's callback to see if the initial value can be set.
353368
std::vector<rclcpp::Parameter> parameter_wrappers {rclcpp::Parameter(name, *initial_value)};
354369
// This function also takes care of default vs initial value.
@@ -413,14 +428,6 @@ declare_parameter_helper(
413428
parameter_descriptor.type = static_cast<uint8_t>(type);
414429
}
415430

416-
if (
417-
rclcpp::PARAMETER_NOT_SET == default_value.get_type() &&
418-
overrides.find(name) == overrides.end() &&
419-
parameter_descriptor.dynamic_typing == false)
420-
{
421-
throw rclcpp::exceptions::NoParameterOverrideProvided(name);
422-
}
423-
424431
rcl_interfaces::msg::ParameterEvent parameter_event;
425432
auto result = __declare_parameter_common(
426433
name,
@@ -806,14 +813,21 @@ NodeParameters::get_parameters(const std::vector<std::string> & names) const
806813
rclcpp::Parameter
807814
NodeParameters::get_parameter(const std::string & name) const
808815
{
809-
rclcpp::Parameter parameter;
816+
std::lock_guard<std::recursive_mutex> lock(mutex_);
810817

811-
if (get_parameter(name, parameter)) {
812-
return parameter;
818+
auto param_iter = parameters_.find(name);
819+
if (
820+
parameters_.end() != param_iter &&
821+
(param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET ||
822+
param_iter->second.descriptor.dynamic_typing))
823+
{
824+
return rclcpp::Parameter{name, param_iter->second.value};
813825
} else if (this->allow_undeclared_) {
814-
return parameter;
815-
} else {
826+
return rclcpp::Parameter{};
827+
} else if (parameters_.end() == param_iter) {
816828
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
829+
} else {
830+
throw rclcpp::exceptions::ParameterUninitializedException(name);
817831
}
818832
}
819833

rclcpp/test/rclcpp/test_node.cpp

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -333,9 +333,14 @@ TEST_F(TestNode, declare_parameter_with_no_initial_values) {
333333
rcl_interfaces::msg::ParameterDescriptor descriptor;
334334
descriptor.dynamic_typing = true;
335335
// no default, no initial
336+
const std::string parameter_name = "parameter"_unq;
336337
rclcpp::ParameterValue value = node->declare_parameter(
337-
"parameter"_unq, rclcpp::ParameterValue{}, descriptor);
338+
parameter_name, rclcpp::ParameterValue{}, descriptor);
338339
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_NOT_SET);
340+
// Does not throw if unset before access
341+
EXPECT_EQ(
342+
rclcpp::PARAMETER_NOT_SET,
343+
node->get_parameter(parameter_name).get_parameter_value().get_type());
339344
}
340345
{
341346
// int default, no initial
@@ -2761,9 +2766,20 @@ TEST_F(TestNode, static_and_dynamic_typing) {
27612766
EXPECT_EQ("hello!", param);
27622767
}
27632768
{
2769+
auto param = node->declare_parameter("integer_override_not_given", rclcpp::PARAMETER_INTEGER);
2770+
EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, param.get_type());
2771+
// Throws if not set before access
27642772
EXPECT_THROW(
2765-
node->declare_parameter("integer_override_not_given", rclcpp::PARAMETER_INTEGER),
2766-
rclcpp::exceptions::NoParameterOverrideProvided);
2773+
node->get_parameter("integer_override_not_given"),
2774+
rclcpp::exceptions::ParameterUninitializedException);
2775+
}
2776+
{
2777+
auto param = node->declare_parameter("integer_set_after_declare", rclcpp::PARAMETER_INTEGER);
2778+
EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, param.get_type());
2779+
auto result = node->set_parameter(rclcpp::Parameter{"integer_set_after_declare", 44});
2780+
ASSERT_TRUE(result.successful) << result.reason;
2781+
auto get_param = node->get_parameter("integer_set_after_declare");
2782+
EXPECT_EQ(44, get_param.as_int());
27672783
}
27682784
{
27692785
EXPECT_THROW(

0 commit comments

Comments
 (0)