Skip to content

Commit 24bb653

Browse files
authored
Enforce static parameter types (#1522)
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
1 parent ab74339 commit 24bb653

14 files changed

+692
-101
lines changed

rclcpp/include/rclcpp/exceptions/exceptions.hpp

+14
Original file line numberDiff line numberDiff line change
@@ -282,6 +282,20 @@ 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
287+
{
288+
public:
289+
/// Construct an instance.
290+
/**
291+
* \param[in] name the name of the parameter.
292+
* \param[in] message custom exception message.
293+
*/
294+
explicit NoParameterOverrideProvided(const std::string & name)
295+
: std::runtime_error("parameter '" + name + "' requires an user provided parameter override")
296+
{}
297+
};
298+
285299
/// Thrown if the QoS overrides provided aren't valid.
286300
class InvalidQosOverridesException : public std::runtime_error
287301
{

rclcpp/include/rclcpp/node.hpp

+56-1
Original file line numberDiff line numberDiff line change
@@ -305,16 +305,59 @@ class Node : public std::enable_shared_from_this<Node>
305305
* name is invalid.
306306
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
307307
* value fails to be set.
308+
* \throws rclcpp::exceptions::InvalidParameterTypeException
309+
* if the type of the default value or override is wrong.
308310
*/
309311
RCLCPP_PUBLIC
310312
const rclcpp::ParameterValue &
311313
declare_parameter(
312314
const std::string & name,
313-
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
315+
const rclcpp::ParameterValue & default_value,
314316
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
315317
rcl_interfaces::msg::ParameterDescriptor(),
316318
bool ignore_override = false);
317319

320+
/// Declare and initialize a parameter, return the effective value.
321+
/**
322+
* Same as the previous one, but a default value is not provided and the user
323+
* must provide a parameter override of the correct type.
324+
*
325+
* \param[in] name The name of the parameter.
326+
* \param[in] type Desired type of the parameter, which will enforced at runtime.
327+
* \param[in] parameter_descriptor An optional, custom description for
328+
* the parameter.
329+
* \param[in] ignore_override When `true`, the parameter override is ignored.
330+
* Default to `false`.
331+
* \return A const reference to the value of the parameter.
332+
* \throws Same as the previous overload taking a default value.
333+
* \throws rclcpp::exceptions::InvalidParameterTypeException
334+
* if an override is not provided or the provided override is of the wrong type.
335+
*/
336+
RCLCPP_PUBLIC
337+
const rclcpp::ParameterValue &
338+
declare_parameter(
339+
const std::string & name,
340+
rclcpp::ParameterType type,
341+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
342+
rcl_interfaces::msg::ParameterDescriptor{},
343+
bool ignore_override = false);
344+
345+
/// Declare a parameter
346+
[[deprecated(
347+
"declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
348+
"If you want to declare a parameter that won't change type without a default value use:\n" \
349+
"`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
350+
"If you want to declare a parameter that can dynamically change type use:\n" \
351+
"```\n" \
352+
"rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
353+
"descriptor.dynamic_typing = true;\n" \
354+
"node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
355+
"```"
356+
)]]
357+
RCLCPP_PUBLIC
358+
const rclcpp::ParameterValue &
359+
declare_parameter(const std::string & name);
360+
318361
/// Declare and initialize a parameter with a type.
319362
/**
320363
* See the non-templated declare_parameter() on this class for details.
@@ -345,6 +388,18 @@ class Node : public std::enable_shared_from_this<Node>
345388
rcl_interfaces::msg::ParameterDescriptor(),
346389
bool ignore_override = false);
347390

391+
/// Declare and initialize a parameter with a type.
392+
/**
393+
* See the non-templated declare_parameter() on this class for details.
394+
*/
395+
template<typename ParameterT>
396+
auto
397+
declare_parameter(
398+
const std::string & name,
399+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
400+
rcl_interfaces::msg::ParameterDescriptor(),
401+
bool ignore_override = false);
402+
348403
/// Declare and initialize several parameters with the same namespace and type.
349404
/**
350405
* For each key in the map, a parameter with a name of "namespace.key"

rclcpp/include/rclcpp/node_impl.hpp

+18
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,24 @@ Node::declare_parameter(
172172
}
173173
}
174174

175+
template<typename ParameterT>
176+
auto
177+
Node::declare_parameter(
178+
const std::string & name,
179+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
180+
bool ignore_override)
181+
{
182+
// get advantage of parameter value template magic to get
183+
// the correct rclcpp::ParameterType from ParameterT
184+
rclcpp::ParameterValue value{ParameterT{}};
185+
return this->declare_parameter(
186+
name,
187+
value.get_type(),
188+
parameter_descriptor,
189+
ignore_override
190+
).get<ParameterT>();
191+
}
192+
175193
template<typename ParameterT>
176194
std::vector<ParameterT>
177195
Node::declare_parameters(

rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp

+31-2
Original file line numberDiff line numberDiff line change
@@ -103,13 +103,42 @@ class NodeParameters : public NodeParametersInterface
103103
virtual
104104
~NodeParameters();
105105

106+
// This is overriding a deprecated method, so we need to ignore the deprecation warning here.
107+
// Users of the method will still get a warning!
108+
#ifndef _WIN32
109+
# pragma GCC diagnostic push
110+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
111+
#else
112+
# pragma warning(push)
113+
# pragma warning(disable: 4996)
114+
#endif
115+
[[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]]
116+
RCLCPP_PUBLIC
117+
const rclcpp::ParameterValue &
118+
declare_parameter(const std::string & name) override;
119+
#ifndef _WIN32
120+
# pragma GCC diagnostic pop
121+
#else
122+
# pragma warning(pop)
123+
#endif
124+
106125
RCLCPP_PUBLIC
107126
const rclcpp::ParameterValue &
108127
declare_parameter(
109128
const std::string & name,
110129
const rclcpp::ParameterValue & default_value,
111-
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
112-
bool ignore_override) override;
130+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
131+
rcl_interfaces::msg::ParameterDescriptor{},
132+
bool ignore_override = false) override;
133+
134+
RCLCPP_PUBLIC
135+
const rclcpp::ParameterValue &
136+
declare_parameter(
137+
const std::string & name,
138+
rclcpp::ParameterType type,
139+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
140+
rcl_interfaces::msg::ParameterDescriptor(),
141+
bool ignore_override = false) override;
113142

114143
RCLCPP_PUBLIC
115144
void

rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp

+35-1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,17 @@ struct OnSetParametersCallbackHandle
4545
OnParametersSetCallbackType callback;
4646
};
4747

48+
#define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE \
49+
"declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
50+
"If you want to declare a parameter that won't change type without a default value use:\n" \
51+
"`node_params->declare_parameter(name, type)`, with e.g. type=rclcpp::PARAMETER_INTEGER.\n\n" \
52+
"If you want to declare a parameter that can dynamically change type use:\n" \
53+
"```\n" \
54+
"rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
55+
"descriptor.dynamic_typing = true;\n" \
56+
"node_params->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
57+
"```"
58+
4859
/// Pure virtual interface class for the NodeParameters part of the Node API.
4960
class NodeParametersInterface
5061
{
@@ -55,6 +66,15 @@ class NodeParametersInterface
5566
virtual
5667
~NodeParametersInterface() = default;
5768

69+
/// Declare a parameter.
70+
/**
71+
* \sa rclcpp::Node::declare_parameter
72+
*/
73+
[[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]]
74+
virtual
75+
const rclcpp::ParameterValue &
76+
declare_parameter(const std::string & name) = 0;
77+
5878
/// Declare and initialize a parameter.
5979
/**
6080
* \sa rclcpp::Node::declare_parameter
@@ -64,7 +84,21 @@ class NodeParametersInterface
6484
const rclcpp::ParameterValue &
6585
declare_parameter(
6686
const std::string & name,
67-
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
87+
const rclcpp::ParameterValue & default_value,
88+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
89+
rcl_interfaces::msg::ParameterDescriptor(),
90+
bool ignore_override = false) = 0;
91+
92+
/// Declare a parameter.
93+
/**
94+
* \sa rclcpp::Node::declare_parameter
95+
*/
96+
RCLCPP_PUBLIC
97+
virtual
98+
const rclcpp::ParameterValue &
99+
declare_parameter(
100+
const std::string & name,
101+
rclcpp::ParameterType type,
68102
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
69103
rcl_interfaces::msg::ParameterDescriptor(),
70104
bool ignore_override = false) = 0;

rclcpp/src/rclcpp/node.cpp

+32
Original file line numberDiff line numberDiff line change
@@ -219,6 +219,24 @@ Node::create_callback_group(
219219
return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
220220
}
221221

222+
const rclcpp::ParameterValue &
223+
Node::declare_parameter(const std::string & name)
224+
{
225+
#ifndef _WIN32
226+
# pragma GCC diagnostic push
227+
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
228+
#else
229+
# pragma warning(push)
230+
# pragma warning(disable: 4996)
231+
#endif
232+
return this->node_parameters_->declare_parameter(name);
233+
#ifndef _WIN32
234+
# pragma GCC diagnostic pop
235+
#else
236+
# pragma warning(pop)
237+
#endif
238+
}
239+
222240
const rclcpp::ParameterValue &
223241
Node::declare_parameter(
224242
const std::string & name,
@@ -233,6 +251,20 @@ Node::declare_parameter(
233251
ignore_override);
234252
}
235253

254+
const rclcpp::ParameterValue &
255+
Node::declare_parameter(
256+
const std::string & name,
257+
rclcpp::ParameterType type,
258+
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
259+
bool ignore_override)
260+
{
261+
return this->node_parameters_->declare_parameter(
262+
name,
263+
type,
264+
parameter_descriptor,
265+
ignore_override);
266+
}
267+
236268
void
237269
Node::undeclare_parameter(const std::string & name)
238270
{

0 commit comments

Comments
 (0)