Skip to content
Merged
Show file tree
Hide file tree
Changes from 21 commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 55 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -305,16 +305,58 @@ class Node : public std::enable_shared_from_this<Node>
* name is invalid.
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
* value fails to be set.
* \throws rclcpp::exceptions::InvalidParameterTypeException
* if the type of the default value or override is wrong.
*/
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);

/// Declare and initialize a parameter, return the effective value.
/**
* Same as the previous one, but a default value is not provided and the user
* must provide a parameter override of the correct type.
*
* \param[in] name The name of the parameter.
* \param[in] type Desired type of the parameter, which will enforced at runtime.
* \param[in] parameter_descriptor An optional, custom description for
* the parameter.
* \param[in] ignore_override When `true`, the parameter override is ignored.
* Default to `false`.
* \return A const reference to the value of the parameter.
* \throws Same as the previous overload taking a default value.
* \throws rclcpp::exceptions::InvalidParameterTypeException
* if an override is not provided or the provided override is of the wrong type.
*/
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor{},
bool ignore_override = false);

[[deprecated(
"declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
"If you want to declare a parameter that won't change type without a default value use:\n" \
"`node->declare_parameter<ParameterT>(name)`, where e.g. ParameterT=int64_t.\n\n" \
"If you want to declare a parameter that can dynamically change type use:\n" \
"```\n" \
"rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
"descriptor.dynamic_typing = true;\n" \
"node->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);" \
"```"
)]]
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(const std::string & name);

/// Declare and initialize a parameter with a type.
/**
* See the non-templated declare_parameter() on this class for details.
Expand Down Expand Up @@ -345,6 +387,18 @@ class Node : public std::enable_shared_from_this<Node>
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);

/// Declare and initialize a parameter with a type.
/**
* See the non-templated declare_parameter() on this class for details.
*/
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);

/// Declare and initialize several parameters with the same namespace and type.
/**
* For each key in the map, a parameter with a name of "namespace.key"
Expand Down
17 changes: 17 additions & 0 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,6 +172,23 @@ Node::declare_parameter(
}
}

template<typename ParameterT>
auto
Node::declare_parameter(
const std::string & name,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override)
{
// get advantage of parameter value template magic to get
// the correct rclcpp::ParameterType from ParameterT
rclcpp::ParameterValue value{ParameterT{}};
return this->declare_parameter(
name,
value.get_type(),
parameter_descriptor,
ignore_override).get<ParameterT>();
}

template<typename ParameterT>
std::vector<ParameterT>
Node::declare_parameters(
Expand Down
33 changes: 31 additions & 2 deletions rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,13 +103,42 @@ class NodeParameters : public NodeParametersInterface
virtual
~NodeParameters();

// This is overriding a deprecated method, so we need to ignore the deprecation warning here.
// Users of the method will still get a warning!
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
[[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]]
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(const std::string & name) override;
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif

RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override) override;
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor{},
bool ignore_override = false) override;

RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false) override;

RCLCPP_PUBLIC
void
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,17 @@ struct OnSetParametersCallbackHandle
OnParametersSetCallbackType callback;
};

#define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE \
"declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
"If you want to declare a parameter that won't change type without a default value use:\n" \
"`node_params->declare_parameter(name, type)`, with e.g. type=rclcpp::PARAMETER_INTEGER.\n\n" \
"If you want to declare a parameter that can dynamically change type use:\n" \
"```\n" \
"rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
"descriptor.dynamic_typing = true;\n" \
"node_params->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);" \
"```"

/// Pure virtual interface class for the NodeParameters part of the Node API.
class NodeParametersInterface
{
Expand All @@ -55,6 +66,15 @@ class NodeParametersInterface
virtual
~NodeParametersInterface() = default;

/// Declare a parameter.
/**
* \sa rclcpp::Node::declare_parameter
*/
[[deprecated(RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE)]]
virtual
const rclcpp::ParameterValue &
declare_parameter(const std::string & name) = 0;

/// Declare and initialize a parameter.
/**
* \sa rclcpp::Node::declare_parameter
Expand All @@ -64,7 +84,21 @@ class NodeParametersInterface
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false) = 0;

/// Declare a parameter.
/**
* \sa rclcpp::Node::declare_parameter
*/
RCLCPP_PUBLIC
virtual
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false) = 0;
Expand Down
32 changes: 32 additions & 0 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,6 +219,24 @@ Node::create_callback_group(
return node_base_->create_callback_group(group_type, automatically_add_to_executor_with_node);
}

const rclcpp::ParameterValue &
Node::declare_parameter(const std::string & name)
{
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
return this->node_parameters_->declare_parameter(name);
#ifndef _WIN32
# pragma GCC diagnostic pop
#else
# pragma warning(pop)
#endif
}

const rclcpp::ParameterValue &
Node::declare_parameter(
const std::string & name,
Expand All @@ -233,6 +251,20 @@ Node::declare_parameter(
ignore_override);
}

const rclcpp::ParameterValue &
Node::declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override)
{
return this->node_parameters_->declare_parameter(
name,
type,
parameter_descriptor,
ignore_override);
}

void
Node::undeclare_parameter(const std::string & name)
{
Expand Down
Loading