@@ -305,16 +305,59 @@ class Node : public std::enable_shared_from_this<Node>
305
305
* name is invalid.
306
306
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
307
307
* value fails to be set.
308
+ * \throws rclcpp::exceptions::InvalidParameterTypeException
309
+ * if the type of the default value or override is wrong.
308
310
*/
309
311
RCLCPP_PUBLIC
310
312
const rclcpp::ParameterValue &
311
313
declare_parameter (
312
314
const std::string & name,
313
- const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue() ,
315
+ const rclcpp::ParameterValue & default_value,
314
316
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
315
317
rcl_interfaces::msg::ParameterDescriptor (),
316
318
bool ignore_override = false);
317
319
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
+
318
361
// / Declare and initialize a parameter with a type.
319
362
/* *
320
363
* See the non-templated declare_parameter() on this class for details.
@@ -345,6 +388,18 @@ class Node : public std::enable_shared_from_this<Node>
345
388
rcl_interfaces::msg::ParameterDescriptor (),
346
389
bool ignore_override = false);
347
390
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
+
348
403
// / Declare and initialize several parameters with the same namespace and type.
349
404
/* *
350
405
* For each key in the map, a parameter with a name of "namespace.key"
0 commit comments