use default parameter descriptor in parameters interface (#765)
* use default parameter descriptor in parameters interface Signed-off-by: Karsten Knese <karsten@openrobotics.org> * use default parameter for value Signed-off-by: Karsten Knese <karsten@openrobotics.org>
This commit is contained in:
parent
2bee266adf
commit
e7c463dc74
1 changed files with 3 additions and 2 deletions
|
@ -51,8 +51,9 @@ public:
|
|||
const rclcpp::ParameterValue &
|
||||
declare_parameter(
|
||||
const std::string & name,
|
||||
const rclcpp::ParameterValue & default_value,
|
||||
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor) = 0;
|
||||
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
|
||||
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
|
||||
rcl_interfaces::msg::ParameterDescriptor()) = 0;
|
||||
|
||||
/// Undeclare a parameter.
|
||||
/**
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue