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:
Karsten Knese 2019-06-20 10:43:44 -07:00 committed by GitHub
parent 2bee266adf
commit e7c463dc74
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23

View file

@ -51,8 +51,9 @@ public:
const rclcpp::ParameterValue & const rclcpp::ParameterValue &
declare_parameter( declare_parameter(
const std::string & name, const std::string & name,
const rclcpp::ParameterValue & default_value, const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor) = 0; const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor()) = 0;
/// Undeclare a parameter. /// Undeclare a parameter.
/** /**