Read only parameters (#495)

* in progress broken test_time_source

Signed-off-by: Shane Loretz <sloretz@osrfoundation.org>

* style

Signed-off-by: Shane Loretz <sloretz@osrfoundation.org>

* test undeclared params

Signed-off-by: Shane Loretz <sloretz@osrfoundation.org>

* Only get parameter if it is set

Signed-off-by: Shane Loretz <sloretz@osrfoundation.org>

* doc fixup

Signed-off-by: William Woodall <william@osrfoundation.org>

* use override rather than virtual in places

Signed-off-by: William Woodall <william@osrfoundation.org>

* rename ParameterInfo_t to ParameterInfo and just use struct, no typedef

Signed-off-by: William Woodall <william@osrfoundation.org>

* add method to access ParameterValue within a Parameter

Signed-off-by: William Woodall <william@osrfoundation.org>

* enable get<Parameter> and get<ParameterValue> on Parameter class

Signed-off-by: William Woodall <william@osrfoundation.org>

* avoid const pass by value

Signed-off-by: William Woodall <william@osrfoundation.org>

* match type of enum in C++ to type used in message definition

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup after rebase

Signed-off-by: William Woodall <william@osrfoundation.org>

* more fixup after rebase

Signed-off-by: William Woodall <william@osrfoundation.org>

* replace create_parameter with declare_parameter

Signed-off-by: William Woodall <william@osrfoundation.org>

* provide implementation for templated declare_parameter method

Signed-off-by: William Woodall <william@osrfoundation.org>

* style

Signed-off-by: William Woodall <william@osrfoundation.org>

* do not use const reference when it's a primitive (like bool)

Signed-off-by: William Woodall <william@osrfoundation.org>

* typo

Signed-off-by: William Woodall <william@osrfoundation.org>

* follow to bool change that wasn't staged

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* added lots of docs, alternative API signatures, and some of the tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* more tests and associated fixes

Signed-off-by: William Woodall <william@osrfoundation.org>

* address documentation feedback

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup previously added tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* add tests and fixes for describe_parameter(s) and get_parameter_types

Signed-off-by: William Woodall <william@osrfoundation.org>

* remove old parameter tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* use const reference where possible

Signed-off-by: William Woodall <william@osrfoundation.org>

* address comments

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix tests for deprecated methods

Signed-off-by: William Woodall <william@osrfoundation.org>

* address feedback

Signed-off-by: William Woodall <william@osrfoundation.org>

* significantly improve the reliability of the time_source tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* uncrustify, cpplint, and cppcheck fixes

Signed-off-by: William Woodall <william@osrfoundation.org>

* Revert "significantly improve the reliability of the time_source tests"

This reverts commit 3ef385d8419c3f71cba91e622138583a91b2682a.

Signed-off-by: William Woodall <william@osrfoundation.org>

* only declare use_sim_time parameter if not already declared

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup rclcpp_lifecycle

Signed-off-by: William Woodall <william@osrfoundation.org>

* fixup tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* add missing namespace scope which fails on Windows

Signed-off-by: William Woodall <william@osrfoundation.org>

* extend deprecation warning suppression to support Windows too

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix compiler warnings and missing visibility macro

Signed-off-by: William Woodall <william@osrfoundation.org>

* remove commented left over tests

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix compiler warning on Windows

Signed-off-by: William Woodall <william@osrfoundation.org>

* suppress deprecation warning on include of file in Windows

Signed-off-by: William Woodall <william@osrfoundation.org>

* avoid potential loss of data warning converting int64_t to int

Signed-off-by: William Woodall <william@osrfoundation.org>

* trying to fix more loss of data warnings

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix test_node

Signed-off-by: William Woodall <william@osrfoundation.org>

* add option to automatically declare parameters from initial parameters (yaml file)

Signed-off-by: William Woodall <william@osrfoundation.org>

* remove redundant conditional

Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
Shane Loretz 2019-04-23 10:44:55 -07:00 committed by William Woodall
parent 97ed34a042
commit 6b10841477
22 changed files with 3070 additions and 371 deletions

View file

@ -210,10 +210,6 @@ if(BUILD_TESTING)
)
target_link_libraries(test_node_global_args ${PROJECT_NAME})
endif()
ament_add_gtest(test_node_initial_parameters test/test_node_initial_parameters.cpp)
if(TARGET test_node_initial_parameters)
target_link_libraries(test_node_initial_parameters ${PROJECT_NAME})
endif()
ament_add_gtest(test_parameter_events_filter test/test_parameter_events_filter.cpp)
if(TARGET test_parameter_events_filter)
ament_target_dependencies(test_parameter_events_filter

View file

@ -185,14 +185,35 @@ public:
class InvalidParametersException : public std::runtime_error
{
public:
// Inherit constructors from runtime_error;
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};
/// Throwing if passed parameter value is invalid.
/// Thrown if passed parameter value is invalid.
class InvalidParameterValueException : public std::runtime_error
{
// Inherit constructors from runtime_error;
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};
/// Thrown if parameter is already declared.
class ParameterAlreadyDeclaredException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};
/// Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
class ParameterNotDeclaredException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};
/// Thrown if parameter is immutable and therefore cannot be undeclared.
class ParameterImmutableException : public std::runtime_error
{
// Inherit constructors from runtime_error.
using std::runtime_error::runtime_error;
};

View file

@ -23,6 +23,7 @@
#include <mutex>
#include <string>
#include <tuple>
#include <utility>
#include <vector>
#include "rcl/error_handling.h"
@ -329,96 +330,437 @@ public:
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
/// Declare and initialize a parameter, return the effective value.
/**
* This method is used to declare that a parameter exists on this node.
* If, at run-time, the user has provided an initial value then it will be
* set in this method, otherwise the given default_value will be set.
* In either case, the resulting value is returned, whether or not it is
* based on the default value or the user provided initial value.
*
* If no parameter_descriptor is given, then the default values from the
* message definition will be used, e.g. read_only will be false.
*
* The name and type in the given rcl_interfaces::msg::ParameterDescriptor
* are ignored, and should be specified using the name argument to this
* function and the default value's type instead.
*
* This method, if successful, will result in any callback registered with
* set_on_parameters_set_callback to be called.
* If that callback prevents the initial value for the parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
* The returned reference will remain valid until the parameter is
* undeclared.
*
* \param[in] name The name of the parameter.
* \param[in] default_value An initial value to be used if at run-time user
* did not override it.
* \param[in] parameter_descriptor An optional, custom description for
* the parameter.
* \return A const reference to the value of the parameter.
* \throws rclcpp::exceptions::ParameterAlreadyDeclaredException if parameter
* has already been declared.
* \throws rclcpp::exceptions::InvalidParametersException if a parameter
* name is invalid.
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
* value fails to be set.
*/
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor());
/// Declare and initialize a parameter with a type.
/**
* See the non-templated declare_parameter() on this class for details.
*
* If the type of the default value, and therefore also the type of return
* value, differs from the initial value provided in the node options, then
* a rclcpp::ParameterTypeException may be thrown.
* To avoid this, use the declare_parameter() method which returns an
* rclcpp::ParameterValue instead.
*
* Note, this method cannot return a const reference, because extending the
* lifetime of a temporary only works recursively with member initializers,
* and cannot be extended to members of a class returned.
* The return value of this class is a copy of the member of a ParameterValue
* which is returned by the other version of declare_parameter().
* See also:
*
* - https://en.cppreference.com/w/cpp/language/lifetime
* - https://herbsutter.com/2008/01/01/gotw-88-a-candidate-for-the-most-important-const/
* - https://www.youtube.com/watch?v=uQyT-5iWUow (cppnow 2018 presentation)
*/
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const ParameterT & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor());
/// 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"
* will be set to the value in the map.
* The resulting value for each declared parameter will be returned.
*
* The name expansion is naive, so if you set the namespace to be "foo.",
* then the resulting parameter names will be like "foo..key".
* However, if the namespace is an empty string, then no leading '.' will be
* placed before each key, which would have been the case when naively
* expanding "namespace.key".
* This allows you to declare several parameters at once without a namespace.
*
* The map may either contain default values for parameters, or a std::pair
* where the first element is a default value and the second is a
* parameter descriptor.
* This function only takes the default value, but there is another overload
* which takes the std::pair with the default value and descriptor.
*
* This method, if successful, will result in any callback registered with
* set_on_parameters_set_callback to be called, once for each parameter.
* If that callback prevents the initial value for any parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
* \param[in] namespace_ The namespace in which to declare the parameters.
* \param[in] parameters The parameters to set in the given namespace.
* \throws rclcpp::exceptions::ParameterAlreadyDeclaredException if parameter
* has already been declared.
* \throws rclcpp::exceptions::InvalidParametersException if a parameter
* name is invalid.
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
* value fails to be set.
*/
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<std::string, ParameterT> & parameters);
/// Declare and initialize several parameters with the same namespace and type.
/**
* This version will take a map where the value is a pair, with the default
* parameter value as the first item and a parameter descriptor as the second.
*
* See the simpler declare_parameters() on this class for more details.
*/
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<
std::string,
std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
> & parameters);
/// Undeclare a previously declared parameter.
/**
* This method will not cause a callback registered with
* set_on_parameters_set_callback to be called.
*
* \param[in] name The name of the parameter to be undeclared.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared.
* \throws rclcpp::exceptions::ParameterImmutableException if the parameter
* was create as read_only (immutable).
*/
RCLCPP_PUBLIC
void
undeclare_parameter(const std::string & name);
/// Return true if a given parameter is declared.
/**
* \param[in] name The name of the parameter to check for being declared.
* \return true if the parameter name has been declared, otherwise false.
*/
RCLCPP_PUBLIC
bool
has_parameter(const std::string & name) const;
/// Set a single parameter.
/**
* Set the given parameter and then return result of the set action.
*
* If the parameter has not been declared this function may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception, but only if
* the node was not created with the
* rclcpp::NodeOptions::allow_undeclared_parameters set to true.
* If undeclared parameters are allowed, then the parameter is implicitly
* declared with the default parameter meta data before being set.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called.
* If the callback prevents the parameter from being set, then it will be
* reflected in the SetParametersResult that is returned, but no exception
* will be thrown.
*
* If the value type of the parameter is rclcpp::PARAMETER_NOT_SET, and the
* existing parameter type is something else, then the parameter will be
* implicitly undeclared.
* This will result in a parameter event indicating that the parameter was
* deleted.
*
* \param[in] parameter The parameter to be set.
* \return The result of the set action.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameter(const rclcpp::Parameter & parameter);
/// Set one or more parameters, one at a time.
/**
* Set the given parameters, one at a time, and then return result of each
* set action.
*
* Parameters are set in the order they are given within the input vector.
*
* Like set_parameter, if any of the parameters to be set have not first been
* declared, and undeclared parameters are not allowed (the default), then
* this method will throw rclcpp::exceptions::ParameterNotDeclaredException.
*
* If setting a parameter fails due to not being declared, then the
* parameters which have already been set will stay set, and no attempt will
* be made to set the parameters which come after.
*
* If a parameter fails to be set due to any other reason, like being
* rejected by the user's callback (basically any reason other than not
* having been declared beforehand), then that is reflected in the
* corresponding SetParametersResult in the vector returned by this function.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called, once for each parameter.
* If the callback prevents the parameter from being set, then, as mentioned
* before, it will be reflected in the corresponding SetParametersResult
* that is returned, but no exception will be thrown.
*
* Like set_parameter() this method will implicitly undeclare parameters
* with the type rclcpp::PARAMETER_NOT_SET.
*
* \param[in] parameters The vector of parameters to be set.
* \return The results for each set action as a vector.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
/// Set one or more parameters, all at once.
/**
* Set the given parameters, all at one time, and then aggregate result.
*
* Behaves like set_parameter, except that it sets multiple parameters,
* failing all if just one of the parameters are unsuccessfully set.
* Either all of the parameters are set or none of them are set.
*
* Like set_parameter and set_parameters, this method may throw an
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* parameters to be set have not first been declared.
* If the exception is thrown then none of the parameters will have been set.
*
* This method will result in any callback registered with
* set_on_parameters_set_callback to be called, just one time.
* If the callback prevents the parameters from being set, then it will be
* reflected in the SetParametersResult which is returned, but no exception
* will be thrown.
*
* If you pass multiple rclcpp::Parameter instances with the same name, then
* only the last one in the vector (forward iteration) will be set.
*
* Like set_parameter() this method will implicitly undeclare parameters
* with the type rclcpp::PARAMETER_NOT_SET.
*
* \param[in] parameters The vector of parameters to be set.
* \return The aggregate result of setting all the parameters atomically.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
/// Set one parameter, unless that parameter has already been set.
/**
* Set the given parameter unless already set.
*
* Deprecated, instead use declare_parameter().
*
* \param[in] parameters The vector of parameters to be set.
* \return The result of each set action as a vector.
*/
template<typename ParameterT>
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
[[deprecated("use declare_parameter() instead")]]
void
set_parameter_if_not_set(
const std::string & name,
const ParameterT & value);
set_parameter_if_not_set(const std::string & name, const ParameterT & value);
/// Set a map of parameters with the same prefix.
/**
* For each key in the map, a parameter with a name of "name.key" will be set
* to the value in the map.
*
* Deprecated, instead use declare_parameters().
*
* \param[in] name The prefix of the parameters to set.
* \param[in] values The parameters to set in the given prefix.
*/
template<typename MapValueT>
template<typename ParameterT>
[[deprecated("use declare_parameters() instead")]]
void
set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values);
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
const std::map<std::string, ParameterT> & values);
/// Return the parameter by the given name.
/**
* If the parameter has not been declared, then this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception.
*
* If undeclared parameters are allowed, see the node option
* rclcpp::NodeOptions::allow_undeclared_parameters, then this method will
* not throw an exception, and instead return a default initialized
* rclcpp::Parameter, which has a type of
* rclcpp::ParameterType::PARAMETER_NOT_SET.
*
* \param[in] name The name of the parameter to get.
* \return The requested parameter inside of a rclcpp parameter object.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
rclcpp::Parameter
get_parameter(const std::string & name) const;
RCLCPP_PUBLIC
bool
get_parameter(
const std::string & name,
rclcpp::Parameter & parameter) const;
/// Assign the value of the parameter if set into the parameter argument.
/// Get the value of a parameter by the given name, and return true if it was set.
/**
* If the parameter was not set, then the "parameter" argument is never assigned a value.
* This method will never throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception, but will
* instead return false if the parameter has not be previously declared.
*
* If the parameter was not declared, then the output argument for this
* method which is called "parameter" will not be assigned a value.
* If the parameter was declared, and therefore has a value, then it is
* assigned into the "parameter" argument of this method.
*
* \param[in] name The name of the parameter to get.
* \param[out] parameter The output where the value of the parameter should be assigned.
* \returns true if the parameter was set, false otherwise
* \param[out] parameter The output storage for the parameter being retrieved.
* \return true if the parameter was previously declared, otherwise false.
*/
RCLCPP_PUBLIC
bool
get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
/// Get the value of a parameter by the given name, and return true if it was set.
/**
* Identical to the non-templated version of this method, except that when
* assigning the output argument called "parameter", this method will attempt
* to coerce the parameter value into the type requested by the given
* template argument, which may fail and throw an exception.
*
* If the parameter has not been declared, it will not attempt to coerce the
* value into the requested type, as it is known that the type is not set.
*
* \throws rclcpp::ParameterTypeException if the requested type does not
* match the value of the parameter which is stored.
*/
template<typename ParameterT>
bool
get_parameter(const std::string & name, ParameterT & parameter) const;
/// Assign the value of the map parameter if set into the values argument.
/// Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
/**
* Parameter names that are part of a map are of the form "name.member".
* This API gets all parameters that begin with "name", storing them into the
* map with the name of the parameter and their value.
* If there are no members in the named map, then the "values" argument is not changed.
*
* \param[in] name The prefix of the parameters to get.
* \param[out] values The map of output values, with one std::string,MapValueT
* per parameter.
* \returns true if values was changed, false otherwise
*/
template<typename MapValueT>
bool
get_parameters(
const std::string & name,
std::map<std::string, MapValueT> & values) const;
/// Get the parameter value, or the "alternative value" if not set, and assign it to "value".
/**
* If the parameter was not set, then the "value" argument is assigned
* If the parameter was not set, then the "parameter" argument is assigned
* the "alternative_value".
* In all cases, the parameter remains not set after this function is called.
*
* Like the version of get_parameter() which returns a bool, this method will
* not throw the rclcpp::exceptions::ParameterNotDeclaredException exception.
*
* In all cases, the parameter is never set or declared within the node.
*
* \param[in] name The name of the parameter to get.
* \param[out] value The output where the value of the parameter should be assigned.
* \param[out] parameter The output where the value of the parameter should be assigned.
* \param[in] alternative_value Value to be stored in output if the parameter was not set.
* \returns true if the parameter was set, false otherwise
* \returns true if the parameter was set, false otherwise.
*/
template<typename ParameterT>
bool
get_parameter_or(
const std::string & name,
ParameterT & value,
ParameterT & parameter,
const ParameterT & alternative_value) const;
/// Return the parameters by the given parameter names.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if the
* requested parameter has not been declared and undeclared parameters are
* not allowed.
*
* Also like get_parameters(), if undeclared parameters are allowed and the
* parameter has not been declared, then the corresponding rclcpp::Parameter
* will be default initialized and therefore have the type
* rclcpp::ParameterType::PARAMETER_NOT_SET.
*
* \param[in] names The names of the parameters to be retrieved.
* \return The parameters that were retrieved.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
*/
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
/// Get the parameter values for all parameters that have a given prefix.
/**
* The "prefix" argument is used to list the parameters which are prefixed
* with that prefix, see also list_parameters().
*
* The resulting list of parameter names are used to get the values of the
* parameters.
*
* The names which are used as keys in the values map have the prefix removed.
* For example, if you use the prefix "foo" and the parameters "foo.ping" and
* "foo.pong" exist, then the returned map will have the keys "ping" and
* "pong".
*
* An empty string for the prefix will match all parameters.
*
* If no parameters with the prefix are found, then the output parameter
* "values" will be unchanged and false will be returned.
* Otherwise, the parameter names and values will be stored in the map and
* true will be returned to indicate "values" was mutated.
*
* This method will never throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception because the
* action of listing the parameters is done atomically with getting the
* values, and therefore they are only listed if already declared and cannot
* be undeclared before being retrieved.
*
* Like the templated get_parameter() variant, this method will attempt to
* coerce the parameter values into the type requested by the given
* template argument, which may fail and throw an exception.
*
* \param[in] prefix The prefix of the parameters to get.
* \param[out] values The map used to store the parameter names and values,
* respectively, with one entry per parameter matching prefix.
* \returns true if output "values" was changed, false otherwise.
* \throws rclcpp::ParameterTypeException if the requested type does not
* match the value of the parameter which is stored.
*/
template<typename ParameterT>
bool
get_parameters(
const std::string & prefix,
std::map<std::string, ParameterT> & values) const;
/// Get the parameter value; if not set, set the "alternative value" and store it in the node.
/**
* If the parameter is set, then the "value" argument is assigned the value
@ -426,36 +768,151 @@ public:
* If the parameter is not set, then the "value" argument is assigned the "alternative_value",
* and the parameter is set to the "alternative_value" on the node.
*
* Deprecated, instead use declare_parameter()'s return value, or use
* has_parameter() to ensure it exists before getting it.
*
* \param[in] name The name of the parameter to get.
* \param[out] value The output where the value of the parameter should be assigned.
* \param[in] alternative_value Value to be stored in output and parameter if the parameter was not set.
* \param[in] alternative_value Value to be used if the parameter was not set.
*/
template<typename ParameterT>
[[deprecated("use declare_parameter() and it's return value instead")]]
void
get_parameter_or_set(
const std::string & name,
ParameterT & value,
const ParameterT & alternative_value);
/// Return the parameter descriptor for the given parameter name.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if the
* requested parameter has not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then a default initialized
* descriptor will be returned.
*
* \param[in] name The name of the parameter to describe.
* \return The descriptor for the given parameter name.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the
* parameter has not been declared and undeclared parameters are not
* allowed.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterDescriptor
describe_parameter(const std::string & name) const;
/// Return a vector of parameter descriptors, one for each of the given names.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* requested parameters have not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then a default initialized
* descriptor will be returned for the undeclared parameter's descriptor.
*
* If the names vector is empty, then an empty vector will be returned.
*
* \param[in] names The list of parameter names to describe.
* \return A list of parameter descriptors, one for each parameter given.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
*/
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(const std::vector<std::string> & names) const;
/// Return a vector of parameter types, one for each of the given names.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* requested parameters have not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then the default type
* rclcpp::ParameterType::PARAMETER_NOT_SET will be returned.
*
* \param[in] names The list of parameter names to get the types.
* \return A list of parameter types, one for each parameter given.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
*/
RCLCPP_PUBLIC
std::vector<uint8_t>
get_parameter_types(const std::vector<std::string> & names) const;
/// Return a list of parameters with any of the given prefixes, up to the given depth.
/**
* \todo: properly document and test this method.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::ListParametersResult
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
using OnParametersSetCallbackType =
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
/// Register a callback to be called anytime a parameter is about to be changed.
/**
* The callback signature is designed to allow handling of any of the above
* `set_parameter*` or `declare_parameter*` methods, and so it takes a const
* reference to a vector of parameters to be set, and returns an instance of
* rcl_interfaces::msg::SetParametersResult to indicate whether or not the
* parameter should be set or not, and if not why.
*
* For an example callback:
*
* rcl_interfaces::msg::SetParametersResult
* my_callback(const std::vector<rclcpp::Parameter> & parameters)
* {
* rcl_interfaces::msg::SetParametersResult result;
* result.successful = true;
* for (const auto & parameter : parameters) {
* if (!some_condition) {
* result.successful = false;
* result.reason = "the reason it could not be allowed";
* }
* }
* return result;
* }
*
* You can see that the SetParametersResult is a boolean flag for success
* and an optional reason that can be used in error reporting when it fails.
*
* This allows the node developer to control which parameters may be changed.
*
* Note that the callback is called when declare_parameter() and its variants
* are called, and so you cannot assume the parameter has been set before
* this callback, so when checking a new value against the existing one, you
* must account for the case where the parameter is not yet set.
*
* Some constraints like read_only are enforced before the callback is called.
*
* There may only be one callback set at a time, so the previously set
* callback is returned when this method is used, or nullptr will be returned
* if no callback was previously set.
*
* \param[in] callback The callback to be called when the value for a
* parameter is about to be set.
* \return The previous callback that was registered, if there was one,
* otherwise nullptr.
*/
RCLCPP_PUBLIC
rclcpp::Node::OnParametersSetCallbackType
set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback);
/// Register the callback for parameter changes
/**
* \param[in] callback User defined callback function.
* It is expected to atomically set parameters.
* \note Repeated invocations of this function will overwrite previous callbacks
* \note Repeated invocations of this function will overwrite previous callbacks.
*/
template<typename CallbackT>
[[deprecated("use set_on_parameters_set_callback() instead")]]
void
register_param_change_callback(CallbackT && callback);

View file

@ -301,11 +301,60 @@ Node::create_service(
group);
}
template<typename CallbackT>
void
Node::register_param_change_callback(CallbackT && callback)
template<typename ParameterT>
auto
Node::declare_parameter(
const std::string & name,
const ParameterT & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
{
this->node_parameters_->register_param_change_callback(std::forward<CallbackT>(callback));
return this->declare_parameter(
name,
rclcpp::ParameterValue(default_value),
parameter_descriptor
).get<ParameterT>();
}
template<typename ParameterT>
std::vector<ParameterT>
Node::declare_parameters(
const std::string & namespace_,
const std::map<std::string, ParameterT> & parameters)
{
std::vector<ParameterT> result;
std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
std::transform(
parameters.begin(), parameters.end(), std::back_inserter(result),
[this, &normalized_namespace](auto element) {
return this->declare_parameter(normalized_namespace + element.first, element.second);
}
);
return result;
}
template<typename ParameterT>
std::vector<ParameterT>
Node::declare_parameters(
const std::string & namespace_,
const std::map<
std::string,
std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
> & parameters)
{
std::vector<ParameterT> result;
std::string normalized_namespace = namespace_.empty() ? "" : (namespace_ + ".");
std::transform(
parameters.begin(), parameters.end(), std::back_inserter(result),
[this, &normalized_namespace](auto element) {
return static_cast<ParameterT>(
this->declare_parameter(
normalized_namespace + element.first,
element.second.first,
element.second.second)
);
}
);
return result;
}
template<typename ParameterT>
@ -314,33 +363,32 @@ Node::set_parameter_if_not_set(
const std::string & name,
const ParameterT & value)
{
std::string parameter_name_with_sub_namespace =
extend_name_with_sub_namespace(name, this->get_sub_namespace());
rclcpp::Parameter parameter;
if (!this->get_parameter(parameter_name_with_sub_namespace, parameter)) {
this->set_parameters({
rclcpp::Parameter(parameter_name_with_sub_namespace, value),
});
if (
!this->has_parameter(name) ||
this->describe_parameter(name).type == PARAMETER_NOT_SET)
{
this->set_parameter(rclcpp::Parameter(name, value));
}
}
// this is a partially-specialized version of set_parameter_if_not_set above,
// where our concrete type for ParameterT is std::map, but the to-be-determined
// type is the value in the map.
template<typename MapValueT>
template<typename ParameterT>
void
Node::set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values)
const std::map<std::string, ParameterT> & values)
{
std::vector<rclcpp::Parameter> params;
for (const auto & val : values) {
std::string param_name = name + "." + val.first;
rclcpp::Parameter parameter;
if (!this->get_parameter(param_name, parameter)) {
params.push_back(rclcpp::Parameter(param_name, val.second));
std::string parameter_name = name + "." + val.first;
if (
!this->has_parameter(parameter_name) ||
this->describe_parameter(parameter_name).type == PARAMETER_NOT_SET)
{
params.push_back(rclcpp::Parameter(parameter_name, val.second));
}
}
@ -349,35 +397,15 @@ Node::set_parameters_if_not_set(
template<typename ParameterT>
bool
Node::get_parameter(const std::string & name, ParameterT & value) const
Node::get_parameter(const std::string & name, ParameterT & parameter) const
{
std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
rclcpp::Parameter parameter;
rclcpp::Parameter parameter_variant;
bool result = get_parameter(sub_name, parameter);
bool result = get_parameter(sub_name, parameter_variant);
if (result) {
value = parameter.get_value<ParameterT>();
}
return result;
}
// this is a partially-specialized version of get_parameter above,
// where our concrete type for ParameterT is std::map, but the to-be-determined
// type is the value in the map.
template<typename MapValueT>
bool
Node::get_parameters(
const std::string & name,
std::map<std::string, MapValueT> & values) const
{
std::map<std::string, rclcpp::Parameter> params;
bool result = node_parameters_->get_parameters_by_prefix(name, params);
if (result) {
for (const auto & param : params) {
values[param.first] = param.second.get_value<MapValueT>();
}
parameter = static_cast<ParameterT>(parameter_variant.get_value<ParameterT>());
}
return result;
@ -387,18 +415,38 @@ template<typename ParameterT>
bool
Node::get_parameter_or(
const std::string & name,
ParameterT & value,
ParameterT & parameter,
const ParameterT & alternative_value) const
{
std::string sub_name = extend_name_with_sub_namespace(name, this->get_sub_namespace());
bool got_parameter = get_parameter(sub_name, value);
bool got_parameter = get_parameter(sub_name, parameter);
if (!got_parameter) {
value = alternative_value;
parameter = alternative_value;
}
return got_parameter;
}
// this is a partially-specialized version of get_parameter above,
// where our concrete type for ParameterT is std::map, but the to-be-determined
// type is the value in the map.
template<typename ParameterT>
bool
Node::get_parameters(
const std::string & prefix,
std::map<std::string, ParameterT> & values) const
{
std::map<std::string, rclcpp::Parameter> params;
bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
if (result) {
for (const auto & param : params) {
values[param.first] = static_cast<ParameterT>(param.second.get_value<ParameterT>());
}
}
return result;
}
template<typename ParameterT>
void
Node::get_parameter_or_set(
@ -417,6 +465,13 @@ Node::get_parameter_or_set(
}
}
template<typename CallbackT>
void
Node::register_param_change_callback(CallbackT && callback)
{
this->node_parameters_->register_param_change_callback(std::forward<CallbackT>(callback));
}
} // namespace rclcpp
#endif // RCLCPP__NODE_IMPL_HPP_

View file

@ -40,6 +40,16 @@ namespace rclcpp
namespace node_interfaces
{
// Internal struct for holding useful info about parameters
struct ParameterInfo
{
/// Current value of the parameter.
rclcpp::ParameterValue value;
/// A description of the parameter
rcl_interfaces::msg::ParameterDescriptor descriptor;
};
/// Implementation of the NodeParameters part of the Node API.
class NodeParameters : public NodeParametersInterface
{
@ -49,6 +59,7 @@ public:
RCLCPP_PUBLIC
NodeParameters(
const node_interfaces::NodeBaseInterface::SharedPtr node_base,
const node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
const node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
const node_interfaces::NodeServicesInterface::SharedPtr node_services,
const node_interfaces::NodeClockInterface::SharedPtr node_clock,
@ -56,76 +67,96 @@ public:
bool use_intra_process,
bool start_parameter_services,
bool start_parameter_event_publisher,
const rmw_qos_profile_t & parameter_event_qos_profile);
const rmw_qos_profile_t & parameter_event_qos_profile,
bool allow_undeclared_parameters,
bool automatically_declare_initial_parameters);
RCLCPP_PUBLIC
virtual
~NodeParameters();
RCLCPP_PUBLIC
virtual
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor) override;
RCLCPP_PUBLIC
void
undeclare_parameter(const std::string & name) override;
RCLCPP_PUBLIC
bool
has_parameter(const std::string & name) const override;
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(
const std::vector<rclcpp::Parameter> & parameters);
const std::vector<rclcpp::Parameter> & parameters) override;
RCLCPP_PUBLIC
virtual
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(
const std::vector<rclcpp::Parameter> & parameters);
const std::vector<rclcpp::Parameter> & parameters) override;
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
get_parameters(const std::vector<std::string> & names) const override;
RCLCPP_PUBLIC
virtual
rclcpp::Parameter
get_parameter(const std::string & name) const;
get_parameter(const std::string & name) const override;
RCLCPP_PUBLIC
virtual
bool
get_parameter(
const std::string & name,
rclcpp::Parameter & parameter) const;
rclcpp::Parameter & parameter) const override;
RCLCPP_PUBLIC
virtual
bool
get_parameters_by_prefix(
const std::string & prefix,
std::map<std::string, rclcpp::Parameter> & parameters) const;
std::map<std::string, rclcpp::Parameter> & parameters) const override;
RCLCPP_PUBLIC
virtual
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(const std::vector<std::string> & names) const;
describe_parameters(const std::vector<std::string> & names) const override;
RCLCPP_PUBLIC
virtual
std::vector<uint8_t>
get_parameter_types(const std::vector<std::string> & names) const;
get_parameter_types(const std::vector<std::string> & names) const override;
RCLCPP_PUBLIC
virtual
rcl_interfaces::msg::ListParametersResult
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const;
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const override;
RCLCPP_PUBLIC
virtual
OnParametersSetCallbackType
set_on_parameters_set_callback(OnParametersSetCallbackType callback) override;
[[deprecated("use set_on_parameters_set_callback() instead")]]
RCLCPP_PUBLIC
void
register_param_change_callback(ParametersCallbackFunction callback);
register_param_change_callback(OnParametersSetCallbackType callback) override;
RCLCPP_PUBLIC
const std::map<std::string, rclcpp::ParameterValue> &
get_initial_parameter_values() const override;
private:
RCLCPP_DISABLE_COPY(NodeParameters)
mutable std::mutex mutex_;
ParametersCallbackFunction parameters_callback_ = nullptr;
OnParametersSetCallbackType on_parameters_set_callback_ = nullptr;
std::map<std::string, rclcpp::Parameter> parameters_;
std::map<std::string, ParameterInfo> parameters_;
std::map<std::string, rclcpp::ParameterValue> initial_parameter_values_;
bool allow_undeclared_ = false;
Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;
@ -133,6 +164,7 @@ private:
std::string combined_name_;
node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
node_interfaces::NodeClockInterface::SharedPtr node_clock_;
};

View file

@ -42,12 +42,49 @@ public:
virtual
~NodeParametersInterface() = default;
/// Declare and initialize a parameter.
/**
* \sa rclcpp::Node::declare_parameter
*/
RCLCPP_PUBLIC
virtual
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor) = 0;
/// Undeclare a parameter.
/**
* \sa rclcpp::Node::undeclare_parameter
*/
RCLCPP_PUBLIC
virtual
void
undeclare_parameter(const std::string & name) = 0;
/// Return true if the parameter has been declared, otherwise false.
/**
* \sa rclcpp::Node::has_parameter
*/
RCLCPP_PUBLIC
virtual
bool
has_parameter(const std::string & name) const = 0;
/// Set one or more parameters, one at a time.
/**
* \sa rclcpp::Node::set_parameters
*/
RCLCPP_PUBLIC
virtual
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(
const std::vector<rclcpp::Parameter> & parameters) = 0;
set_parameters(const std::vector<rclcpp::Parameter> & parameters) = 0;
/// Set and initialize a parameter, all at once.
/**
* \sa rclcpp::Node::set_parameters_atomically
*/
RCLCPP_PUBLIC
virtual
rcl_interfaces::msg::SetParametersResult
@ -119,14 +156,34 @@ public:
rcl_interfaces::msg::ListParametersResult
list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const = 0;
using ParametersCallbackFunction = std::function<
rcl_interfaces::msg::SetParametersResult(
const std::vector<rclcpp::Parameter> &)>;
using OnParametersSetCallbackType =
std::function<
rcl_interfaces::msg::SetParametersResult(const std::vector<rclcpp::Parameter> &)
>;
using ParametersCallbackFunction [[deprecated("use OnParametersSetCallbackType instead")]] =
OnParametersSetCallbackType;
/// Register a callback for when parameters are being set, return an existing one.
/**
* \sa rclcpp::Node::set_on_parameters_set_callback
*/
RCLCPP_PUBLIC
virtual
OnParametersSetCallbackType
set_on_parameters_set_callback(OnParametersSetCallbackType callback) = 0;
[[deprecated("use set_on_parameters_set_callback() instead")]]
RCLCPP_PUBLIC
virtual
void
register_param_change_callback(ParametersCallbackFunction callback) = 0;
register_param_change_callback(OnParametersSetCallbackType callback) = 0;
/// Return the initial parameter values used by the NodeParameters to override default values.
RCLCPP_PUBLIC
virtual
const std::map<std::string, rclcpp::ParameterValue> &
get_initial_parameter_values() const = 0;
};
} // namespace node_interfaces

View file

@ -44,6 +44,8 @@ public:
* - start_parameter_services = true
* - start_parameter_event_publisher = true
* - parameter_event_qos_profile = rmw_qos_profile_parameter_events
* - allow_undeclared_parameters = false
* - automatically_declare_initial_parameters = false
* - allocator = rcl_get_default_allocator()
*
* \param[in] allocator allocator to use in construction of NodeOptions.
@ -129,9 +131,9 @@ public:
return *this;
}
/// Return a reference to the use_global_arguments flag.
/// Return the use_global_arguments flag.
RCLCPP_PUBLIC
const bool &
bool
use_global_arguments() const;
/// Set the use_global_arguments flag, return this for parameter idiom.
@ -144,11 +146,11 @@ public:
*/
RCLCPP_PUBLIC
NodeOptions &
use_global_arguments(const bool & use_global_arguments);
use_global_arguments(bool use_global_arguments);
/// Return a reference to the use_intra_process_comms flag
/// Return the use_intra_process_comms flag.
RCLCPP_PUBLIC
const bool &
bool
use_intra_process_comms() const;
/// Set the use_intra_process_comms flag, return this for parameter idiom.
@ -163,11 +165,11 @@ public:
*/
RCLCPP_PUBLIC
NodeOptions &
use_intra_process_comms(const bool & use_intra_process_comms);
use_intra_process_comms(bool use_intra_process_comms);
/// Return a reference to the start_parameter_services flag
/// Return the start_parameter_services flag.
RCLCPP_PUBLIC
const bool &
bool
start_parameter_services() const;
/// Set the start_parameter_services flag, return this for parameter idiom.
@ -182,11 +184,11 @@ public:
*/
RCLCPP_PUBLIC
NodeOptions &
start_parameter_services(const bool & start_parameter_services);
start_parameter_services(bool start_parameter_services);
/// Return a reference to the start_parameter_event_publisher flag.
/// Return the start_parameter_event_publisher flag.
RCLCPP_PUBLIC
const bool &
bool
start_parameter_event_publisher() const;
/// Set the start_parameter_event_publisher flag, return this for parameter idiom.
@ -198,7 +200,7 @@ public:
*/
RCLCPP_PUBLIC
NodeOptions &
start_parameter_event_publisher(const bool & start_parameter_event_publisher);
start_parameter_event_publisher(bool start_parameter_event_publisher);
/// Return a reference to the parameter_event_qos_profile QoS.
RCLCPP_PUBLIC
@ -213,6 +215,40 @@ public:
NodeOptions &
parameter_event_qos_profile(const rmw_qos_profile_t & parameter_event_qos_profile);
/// Return the allow_undeclared_parameters flag.
RCLCPP_PUBLIC
bool
allow_undeclared_parameters() const;
/// Set the allow_undeclared_parameters, return this for parameter idiom.
/**
* If true, allow any parameter name to be set on the node without first
* being declared.
* Otherwise, setting an undeclared parameter will raise an exception.
*/
RCLCPP_PUBLIC
NodeOptions &
allow_undeclared_parameters(bool allow_undeclared_parameters);
/// Return the automatically_declare_initial_parameters flag.
RCLCPP_PUBLIC
bool
automatically_declare_initial_parameters() const;
/// Set the automatically_declare_initial_parameters, return this.
/**
* If true, automatically iterate through the node's initial parameters and
* implicitly declare any that have not already been declared.
* Otherwise, parameters passed to the node's initial_parameters, and/or the
* global initial parameter values, which are not explicitly declared will
* not appear on the node at all.
* Already declared parameters will not be re-declared, and parameters
* declared in this way will use the default constructed ParameterDescriptor.
*/
RCLCPP_PUBLIC
NodeOptions &
automatically_declare_initial_parameters(bool automatically_declare_initial_parameters);
/// Return the rcl_allocator_t to be used.
RCLCPP_PUBLIC
const rcl_allocator_t &
@ -256,6 +292,10 @@ private:
rmw_qos_profile_t parameter_event_qos_profile_ {rmw_qos_profile_parameter_events};
bool allow_undeclared_parameters_ {false};
bool automatically_declare_initial_parameters_ {false};
rcl_allocator_t allocator_ {rcl_get_default_allocator()};
};

View file

@ -28,21 +28,59 @@
namespace rclcpp
{
class Parameter;
namespace node_interfaces
{
struct ParameterInfo;
} // namespace node_interfaces
namespace detail
{
// This helper function is required because you cannot do specialization on a
// class method, so instead we specialize this template function and call it
// from the unspecialized, but dependent, class method.
template<typename T>
auto
get_value_helper(const rclcpp::Parameter * parameter);
} // namespace detail
/// Structure to store an arbitrary parameter with templated get/set methods.
class Parameter
{
public:
/// Construct with an empty name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
RCLCPP_PUBLIC
Parameter();
/// Construct with given name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
RCLCPP_PUBLIC
explicit Parameter(const std::string & name);
/// Construct with given name and given parameter value.
RCLCPP_PUBLIC
Parameter(const std::string & name, const ParameterValue & value);
/// Construct with given name and given parameter value.
template<typename ValueTypeT>
explicit Parameter(const std::string & name, ValueTypeT value)
Parameter(const std::string & name, ValueTypeT value)
: Parameter(name, ParameterValue(value))
{
}
{}
RCLCPP_PUBLIC
explicit Parameter(const rclcpp::node_interfaces::ParameterInfo & parameter_info);
/// Equal operator.
RCLCPP_PUBLIC
bool
operator==(const Parameter & rhs) const;
/// Not equal operator.
RCLCPP_PUBLIC
bool
operator!=(const Parameter & rhs) const;
RCLCPP_PUBLIC
ParameterType
@ -60,6 +98,11 @@ public:
rcl_interfaces::msg::ParameterValue
get_value_message() const;
/// Get the internal storage for the parameter value.
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
get_parameter_value() const;
/// Get value of parameter using rclcpp::ParameterType as template argument.
template<ParameterType ParamT>
decltype(auto)
@ -71,10 +114,7 @@ public:
/// Get value of parameter using c++ types as template argument.
template<typename T>
decltype(auto)
get_value() const
{
return value_.get<T>();
}
get_value() const;
RCLCPP_PUBLIC
bool
@ -142,6 +182,49 @@ RCLCPP_PUBLIC
std::ostream &
operator<<(std::ostream & os, const std::vector<Parameter> & parameters);
namespace detail
{
template<typename T>
auto
get_value_helper(const rclcpp::Parameter * parameter)
{
return parameter->get_parameter_value().get<T>();
}
// Specialization allowing Parameter::get() to return a const ref to the parameter value object.
template<>
inline
auto
get_value_helper<rclcpp::ParameterValue>(const rclcpp::Parameter * parameter)
{
return parameter->get_parameter_value();
}
// Specialization allowing Parameter::get() to return a const ref to the parameter itself.
template<>
inline
auto
get_value_helper<rclcpp::Parameter>(const rclcpp::Parameter * parameter)
{
// Use this lambda to ensure it's a const reference being returned (and not a copy).
auto type_enforcing_lambda =
[&parameter]() -> const rclcpp::Parameter & {
return *parameter;
};
return type_enforcing_lambda();
}
} // namespace detail
template<typename T>
decltype(auto)
Parameter::get_value() const
{
// use the helper to specialize for the ParameterValue and Parameter cases.
return detail::get_value_helper<T>(this);
}
} // namespace rclcpp
namespace std

View file

@ -43,7 +43,7 @@ public:
explicit ParameterService(
const std::shared_ptr<node_interfaces::NodeBaseInterface> node_base,
const std::shared_ptr<node_interfaces::NodeServicesInterface> node_services,
node_interfaces::NodeParametersInterface * node_params,
rclcpp::node_interfaces::NodeParametersInterface * node_params,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
private:

View file

@ -28,7 +28,8 @@
namespace rclcpp
{
enum ParameterType
enum ParameterType : uint8_t
{
PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
@ -45,11 +46,11 @@ enum ParameterType
/// Return the name of a parameter type
RCLCPP_PUBLIC
std::string
to_string(const ParameterType type);
to_string(ParameterType type);
RCLCPP_PUBLIC
std::ostream &
operator<<(std::ostream & os, const ParameterType type);
operator<<(std::ostream & os, ParameterType type);
/// Indicate the parameter type does not match the expected type.
class ParameterTypeException : public std::runtime_error
@ -129,10 +130,21 @@ public:
rcl_interfaces::msg::ParameterValue
to_value_msg() const;
/// Equal operator.
RCLCPP_PUBLIC
bool
operator==(const ParameterValue & rhs) const;
/// Not equal operator.
RCLCPP_PUBLIC
bool
operator!=(const ParameterValue & rhs) const;
// The following get() variants require the use of ParameterType
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
constexpr
typename std::enable_if<type == ParameterType::PARAMETER_BOOL, const bool &>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
@ -142,7 +154,8 @@ public:
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
constexpr
typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, const int64_t &>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
@ -152,7 +165,8 @@ public:
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::type
constexpr
typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, const double &>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
@ -162,6 +176,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
get() const
{
@ -172,6 +187,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<
type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector<uint8_t> &>::type
get() const
@ -183,6 +199,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<
type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector<bool> &>::type
get() const
@ -194,6 +211,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<
type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector<int64_t> &>::type
get() const
@ -205,6 +223,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<
type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector<double> &>::type
get() const
@ -216,6 +235,7 @@ public:
}
template<ParameterType type>
constexpr
typename std::enable_if<
type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector<std::string> &>::type
get() const
@ -229,28 +249,32 @@ public:
// The following get() variants allow the use of primitive types
template<typename type>
typename std::enable_if<std::is_same<type, bool>::value, bool>::type
constexpr
typename std::enable_if<std::is_same<type, bool>::value, const bool &>::type
get() const
{
return get<ParameterType::PARAMETER_BOOL>();
}
template<typename type>
constexpr
typename std::enable_if<
std::is_integral<type>::value && !std::is_same<type, bool>::value, int64_t>::type
std::is_integral<type>::value && !std::is_same<type, bool>::value, const int64_t &>::type
get() const
{
return get<ParameterType::PARAMETER_INTEGER>();
}
template<typename type>
typename std::enable_if<std::is_floating_point<type>::value, double>::type
constexpr
typename std::enable_if<std::is_floating_point<type>::value, const double &>::type
get() const
{
return get<ParameterType::PARAMETER_DOUBLE>();
}
template<typename type>
constexpr
typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
get() const
{
@ -258,6 +282,7 @@ public:
}
template<typename type>
constexpr
typename std::enable_if<
std::is_convertible<
type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
@ -267,6 +292,7 @@ public:
}
template<typename type>
constexpr
typename std::enable_if<
std::is_convertible<
type, const std::vector<bool> &>::value, const std::vector<bool> &>::type
@ -276,6 +302,7 @@ public:
}
template<typename type>
constexpr
typename std::enable_if<
std::is_convertible<
type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
@ -285,6 +312,7 @@ public:
}
template<typename type>
constexpr
typename std::enable_if<
std::is_convertible<
type, const std::vector<double> &>::value, const std::vector<double> &>::type
@ -294,6 +322,7 @@ public:
}
template<typename type>
constexpr
typename std::enable_if<
std::is_convertible<
type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type

View file

@ -27,7 +27,17 @@
#include "rclcpp/node_interfaces/node_clock.hpp"
#include "rclcpp/node_interfaces/node_graph.hpp"
#include "rclcpp/node_interfaces/node_logging.hpp"
// When compiling this file, Windows produces a deprecation warning for the
// deprecated function prototype of NodeParameters::register_param_change_callback().
// Other compilers do not.
#if defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
#include "rclcpp/node_interfaces/node_parameters.hpp"
#if defined(_WIN32)
# pragma warning(pop)
#endif
#include "rclcpp/node_interfaces/node_services.hpp"
#include "rclcpp/node_interfaces/node_time_source.hpp"
#include "rclcpp/node_interfaces/node_timers.hpp"
@ -114,6 +124,7 @@ Node::Node(
)),
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
node_base_,
node_logging_,
node_topics_,
node_services_,
node_clock_,
@ -121,7 +132,9 @@ Node::Node(
options.use_intra_process_comms(),
options.start_parameter_services(),
options.start_parameter_event_publisher(),
options.parameter_event_qos_profile()
options.parameter_event_qos_profile(),
options.allow_undeclared_parameters(),
options.automatically_declare_initial_parameters()
)),
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
node_base_,
@ -215,20 +228,57 @@ Node::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group)
return node_base_->callback_group_in_node(group);
}
const rclcpp::ParameterValue &
Node::declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
{
return this->node_parameters_->declare_parameter(name, default_value, parameter_descriptor);
}
void
Node::undeclare_parameter(const std::string & name)
{
this->node_parameters_->undeclare_parameter(name);
}
bool
Node::has_parameter(const std::string & name) const
{
return this->node_parameters_->has_parameter(name);
}
rcl_interfaces::msg::SetParametersResult
Node::set_parameter(const rclcpp::Parameter & parameter)
{
return this->set_parameters_atomically({parameter});
}
std::vector<rcl_interfaces::msg::SetParametersResult>
Node::set_parameters(
const std::vector<rclcpp::Parameter> & parameters)
Node::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters(parameters);
}
rcl_interfaces::msg::SetParametersResult
Node::set_parameters_atomically(
const std::vector<rclcpp::Parameter> & parameters)
Node::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters_atomically(parameters);
}
rclcpp::Parameter
Node::get_parameter(const std::string & name) const
{
return node_parameters_->get_parameter(name);
}
bool
Node::get_parameter(const std::string & name, rclcpp::Parameter & parameter) const
{
return node_parameters_->get_parameter(name, parameter);
}
std::vector<rclcpp::Parameter>
Node::get_parameters(
const std::vector<std::string> & names) const
@ -236,40 +286,43 @@ Node::get_parameters(
return node_parameters_->get_parameters(names);
}
rclcpp::Parameter
Node::get_parameter(const std::string & name) const
rcl_interfaces::msg::ParameterDescriptor
Node::describe_parameter(const std::string & name) const
{
return node_parameters_->get_parameter(name);
}
bool Node::get_parameter(
const std::string & name,
rclcpp::Parameter & parameter) const
{
return node_parameters_->get_parameter(name, parameter);
auto result = node_parameters_->describe_parameters({name});
if (0 == result.size()) {
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
}
if (result.size() > 1) {
throw std::runtime_error("number of described parameters unexpectedly more than one");
}
return result.front();
}
std::vector<rcl_interfaces::msg::ParameterDescriptor>
Node::describe_parameters(
const std::vector<std::string> & names) const
Node::describe_parameters(const std::vector<std::string> & names) const
{
return node_parameters_->describe_parameters(names);
}
std::vector<uint8_t>
Node::get_parameter_types(
const std::vector<std::string> & names) const
Node::get_parameter_types(const std::vector<std::string> & names) const
{
return node_parameters_->get_parameter_types(names);
}
rcl_interfaces::msg::ListParametersResult
Node::list_parameters(
const std::vector<std::string> & prefixes, uint64_t depth) const
Node::list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const
{
return node_parameters_->list_parameters(prefixes, depth);
}
rclcpp::Node::OnParametersSetCallbackType
Node::set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback)
{
return node_parameters_->set_on_parameters_set_callback(callback);
}
std::vector<std::string>
Node::get_node_names() const
{

View file

@ -12,7 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.
// When compiling this file, Windows produces a deprecation warning for the
// deprecated function prototype of NodeParameters::register_param_change_callback().
// Other compilers do not.
#if defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
#include "rclcpp/node_interfaces/node_parameters.hpp"
#if defined(_WIN32)
# pragma warning(pop)
#endif
#include <rcl_yaml_param_parser/parser.h>
@ -34,6 +44,7 @@ using rclcpp::node_interfaces::NodeParameters;
NodeParameters::NodeParameters(
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
@ -41,8 +52,13 @@ NodeParameters::NodeParameters(
bool use_intra_process,
bool start_parameter_services,
bool start_parameter_event_publisher,
const rmw_qos_profile_t & parameter_event_qos_profile)
: events_publisher_(nullptr), node_clock_(node_clock)
const rmw_qos_profile_t & parameter_event_qos_profile,
bool allow_undeclared_parameters,
bool automatically_declare_initial_parameters)
: allow_undeclared_(allow_undeclared_parameters),
events_publisher_(nullptr),
node_logging_(node_logging),
node_clock_(node_clock)
{
using MessageT = rcl_interfaces::msg::ParameterEvent;
using PublisherT = rclcpp::Publisher<MessageT>;
@ -118,8 +134,6 @@ NodeParameters::NodeParameters(
combined_name_ = node_namespace + '/' + node_name;
}
std::map<std::string, rclcpp::Parameter> parameters;
// TODO(sloretz) use rcl to parse yaml when circular dependency is solved
// See https://github.com/ros2/rcl/issues/252
for (const std::string & yaml_path : yaml_paths) {
@ -144,27 +158,27 @@ NodeParameters::NodeParameters(
// Combine parameter yaml files, overwriting values in older ones
for (auto & param : iter->second) {
parameters[param.get_name()] = param;
initial_parameter_values_[param.get_name()] =
rclcpp::ParameterValue(param.get_value_message());
}
}
// initial values passed to constructor overwrite yaml file sources
for (auto & param : initial_parameters) {
parameters[param.get_name()] = param;
initial_parameter_values_[param.get_name()] =
rclcpp::ParameterValue(param.get_value_message());
}
std::vector<rclcpp::Parameter> combined_values;
combined_values.reserve(parameters.size());
for (auto & kv : parameters) {
combined_values.emplace_back(kv.second);
}
// TODO(sloretz) store initial values and use them when a parameter is created ros2/rclcpp#475
// Set initial parameter values
if (!combined_values.empty()) {
rcl_interfaces::msg::SetParametersResult result = set_parameters_atomically(combined_values);
if (!result.successful) {
throw std::runtime_error("Failed to set initial parameters");
// If asked, initialize any parameters that ended up in the initial parameter values,
// but did not get declared explcitily by this point.
if (automatically_declare_initial_parameters) {
for (const auto & pair : this->get_initial_parameter_values()) {
if (!this->has_parameter(pair.first)) {
this->declare_parameter(
pair.first,
pair.second,
rcl_interfaces::msg::ParameterDescriptor());
}
}
}
}
@ -172,75 +186,351 @@ NodeParameters::NodeParameters(
NodeParameters::~NodeParameters()
{}
RCLCPP_LOCAL
bool
__lockless_has_parameter(
const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
const std::string & name)
{
return parameters.find(name) != parameters.end();
}
using OnParametersSetCallbackType =
rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
RCLCPP_LOCAL
rcl_interfaces::msg::SetParametersResult
__set_parameters_atomically_common(
const std::vector<rclcpp::Parameter> & parameters,
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
OnParametersSetCallbackType on_set_parameters_callback)
{
// Call the user callback to see if the new value(s) are allowed.
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
if (on_set_parameters_callback) {
result = on_set_parameters_callback(parameters);
}
// If accepted, actually set the values.
if (result.successful) {
for (size_t i = 0; i < parameters.size(); ++i) {
const std::string & name = parameters[i].get_name();
parameter_infos[name].descriptor.name = parameters[i].get_name();
parameter_infos[name].descriptor.type = parameters[i].get_type();
parameter_infos[name].value = parameters[i].get_parameter_value();
}
}
// Either way, return the result.
return result;
}
RCLCPP_LOCAL
rcl_interfaces::msg::SetParametersResult
__declare_parameter_common(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
const std::map<std::string, rclcpp::ParameterValue> & initial_values,
OnParametersSetCallbackType on_set_parameters_callback,
rcl_interfaces::msg::ParameterEvent * parameter_event_out)
{
using rclcpp::node_interfaces::ParameterInfo;
std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
parameter_infos.at(name).descriptor = parameter_descriptor;
// Use the value from the initial_values if available, otherwise use the default.
const rclcpp::ParameterValue * initial_value = &default_value;
auto initial_value_it = initial_values.find(name);
if (initial_value_it != initial_values.end()) {
initial_value = &initial_value_it->second;
}
// Check with the user's callback to see if the initial value can be set.
std::vector<rclcpp::Parameter> parameter_wrappers {rclcpp::Parameter(name, *initial_value)};
// This function also takes care of default vs initial value.
auto result = __set_parameters_atomically_common(
parameter_wrappers,
parameter_infos,
on_set_parameters_callback);
// Add declared parameters to storage.
parameters_out[name] = parameter_infos.at(name);
// Extend the given parameter event, if valid.
if (parameter_event_out) {
parameter_event_out->new_parameters.push_back(parameter_wrappers[0].to_parameter_msg());
}
return result;
}
const rclcpp::ParameterValue &
NodeParameters::declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
{
std::lock_guard<std::mutex> lock(mutex_);
// TODO(sloretz) parameter name validation
if (name.empty()) {
throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
}
// Error if this parameter has already been declared and is different
if (__lockless_has_parameter(parameters_, name)) {
throw rclcpp::exceptions::ParameterAlreadyDeclaredException(
"parameter '" + name + "' has already been declared");
}
rcl_interfaces::msg::ParameterEvent parameter_event;
auto result = __declare_parameter_common(
name,
default_value,
parameter_descriptor,
parameters_,
initial_parameter_values_,
on_parameters_set_callback_,
&parameter_event);
// If it failed to be set, then throw an exception.
if (!result.successful) {
throw rclcpp::exceptions::InvalidParameterValueException(
"parameter '" + name + "' could not be set: " + result.reason);
}
// Publish the event.
events_publisher_->publish(parameter_event);
return parameters_.at(name).value;
}
void
NodeParameters::undeclare_parameter(const std::string & name)
{
std::lock_guard<std::mutex> lock(mutex_);
auto parameter_info = parameters_.find(name);
if (parameter_info == parameters_.end()) {
throw rclcpp::exceptions::ParameterNotDeclaredException(
"cannot undeclare parameter '" + name + "' which has not yet been declared");
}
if (parameter_info->second.descriptor.read_only) {
throw rclcpp::exceptions::ParameterImmutableException(
"cannot undeclare parameter '" + name + "' because it is read-only");
}
parameters_.erase(parameter_info);
}
bool
NodeParameters::has_parameter(const std::string & name) const
{
std::lock_guard<std::mutex> lock(mutex_);
return __lockless_has_parameter(parameters_, name);
}
std::vector<rcl_interfaces::msg::SetParametersResult>
NodeParameters::set_parameters(
const std::vector<rclcpp::Parameter> & parameters)
NodeParameters::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
{
std::vector<rcl_interfaces::msg::SetParametersResult> results;
results.reserve(parameters.size());
for (const auto & p : parameters) {
auto result = set_parameters_atomically({{p}});
results.push_back(result);
}
return results;
}
template<typename ParameterVectorType>
auto
__find_parameter_by_name(
ParameterVectorType & parameters,
const std::string & name)
{
return std::find_if(
parameters.begin(),
parameters.end(),
[&](auto parameter) {return parameter.get_name() == name;});
}
rcl_interfaces::msg::SetParametersResult
NodeParameters::set_parameters_atomically(
const std::vector<rclcpp::Parameter> & parameters)
NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::mutex> lock(mutex_);
std::map<std::string, rclcpp::Parameter> tmp_map;
auto parameter_event = std::make_shared<rcl_interfaces::msg::ParameterEvent>();
parameter_event->node = combined_name_;
// TODO(jacquelinekay): handle parameter constraints
rcl_interfaces::msg::SetParametersResult result;
if (parameters_callback_) {
result = parameters_callback_(parameters);
} else {
result.successful = true;
// Check if any of the parameters are read-only, or if any parameters are not
// declared.
// If not declared, keep track of them in order to declare them later, when
// undeclared parameters are allowed, and if they're not allowed, fail.
std::vector<const rclcpp::Parameter *> parameters_to_be_declared;
for (const auto & parameter : parameters) {
const std::string & name = parameter.get_name();
// Check to make sure the parameter name is valid.
if (name.empty()) {
throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
}
// Check to see if it is declared.
auto parameter_info = parameters_.find(name);
if (parameter_info == parameters_.end()) {
// If not check to see if undeclared paramaters are allowed, ...
if (allow_undeclared_) {
// If so, mark the parameter to be declared for the user implicitly.
parameters_to_be_declared.push_back(&parameter);
// continue as it cannot be read-only, and because the declare will
// implicitly set the parameter and parameter_infos is for setting only.
continue;
} else {
// If not, then throw the exception as documented.
throw rclcpp::exceptions::ParameterNotDeclaredException(
"parameter '" + name + "' cannot be set because it was not declared");
}
}
// Check to see if it is read-only.
if (parameter_info->second.descriptor.read_only) {
result.successful = false;
result.reason = "parameter '" + name + "' cannot be set because it is read-only";
return result;
}
}
// Declare parameters into a temporary "staging area", incase one of the declares fail.
// We will use the staged changes as input to the "set atomically" action.
// We explicitly avoid calling the user callback here, so that it may be called once, with
// all the other parameters to be set (already declared parameters).
std::map<std::string, rclcpp::node_interfaces::ParameterInfo> staged_parameter_changes;
rcl_interfaces::msg::ParameterEvent parameter_event_msg;
parameter_event_msg.node = combined_name_;
for (auto parameter_to_be_declared : parameters_to_be_declared) {
// This should not throw, because we validated the name and checked that
// the parameter was not already declared.
result = __declare_parameter_common(
parameter_to_be_declared->get_name(),
parameter_to_be_declared->get_parameter_value(),
rcl_interfaces::msg::ParameterDescriptor(), // Implicit declare uses default descriptor.
staged_parameter_changes,
initial_parameter_values_,
nullptr, // callback is explicitly null, so that it is called only once, when setting below.
&parameter_event_msg);
if (!result.successful) {
// Declare failed, return knowing that nothing was changed because the
// staged changes were not applied.
return result;
}
}
// If there were implicitly declared parameters, then we may need to copy the input parameters
// and then assign the value that was selected after the declare (could be affected by the
// initial parameter values).
const std::vector<rclcpp::Parameter> * parameters_to_be_set = &parameters;
std::vector<rclcpp::Parameter> parameters_copy;
if (0 != staged_parameter_changes.size()) { // If there were any implicitly declared parameters.
bool any_initial_values_used = false;
for (const auto & staged_parameter_change : staged_parameter_changes) {
auto it = __find_parameter_by_name(parameters, staged_parameter_change.first);
if (it->get_parameter_value() != staged_parameter_change.second.value) {
// In this case, the value of the staged parameter differs from the
// input from the user, and therefore we need to update things before setting.
any_initial_values_used = true;
// No need to search further since at least one initial value needs to be used.
break;
}
}
if (any_initial_values_used) {
parameters_copy = parameters;
for (const auto & staged_parameter_change : staged_parameter_changes) {
auto it = __find_parameter_by_name(parameters_copy, staged_parameter_change.first);
*it = Parameter(staged_parameter_change.first, staged_parameter_change.second.value);
}
parameters_to_be_set = &parameters_copy;
}
}
// Collect parameters who will have had their type changed to
// rclcpp::PARAMETER_NOT_SET so they can later be implicitly undeclared.
std::vector<const rclcpp::Parameter *> parameters_to_be_undeclared;
for (const auto & parameter : *parameters_to_be_set) {
if (rclcpp::PARAMETER_NOT_SET == parameter.get_type()) {
auto it = parameters_.find(parameter.get_name());
if (it != parameters_.end() && rclcpp::PARAMETER_NOT_SET != it->second.value.get_type()) {
parameters_to_be_undeclared.push_back(&parameter);
}
}
}
// Set the all of the parameters including the ones declared implicitly above.
result = __set_parameters_atomically_common(
// either the original parameters given by the user, or ones updated with initial values
*parameters_to_be_set,
// they are actually set on the official parameter storage
parameters_,
// this will get called once, with all the parameters to be set
on_parameters_set_callback_);
// If not successful, then stop here.
if (!result.successful) {
return result;
}
for (const auto & p : parameters) {
if (p.get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) {
if (parameters_.find(p.get_name()) != parameters_.end()) {
// case: parameter was set before, and input is "NOT_SET"
// therefore we will erase the parameter from parameters_ later
parameter_event->deleted_parameters.push_back(p.to_parameter_msg());
}
} else {
if (parameters_.find(p.get_name()) == parameters_.end()) {
// case: parameter not set before, and input is something other than "NOT_SET"
parameter_event->new_parameters.push_back(p.to_parameter_msg());
} else {
// case: parameter was set before, and input is something other than "NOT_SET"
parameter_event->changed_parameters.push_back(p.to_parameter_msg());
}
tmp_map[p.get_name()] = p;
}
// If successful, then update the parameter infos from the implicitly declared parameter's.
for (const auto & kv_pair : staged_parameter_changes) {
// assumption: the parameter is already present in parameters_ due to the above "set"
assert(__lockless_has_parameter(parameters_, kv_pair.first));
// assumption: the value in parameters_ is the same as the value resulting from the declare
assert(parameters_[kv_pair.first].value == kv_pair.second.value);
// This assignment should not change the name, type, or value, but may
// change other things from the ParameterInfo.
parameters_[kv_pair.first] = kv_pair.second;
}
// std::map::insert will not overwrite elements, so we'll keep the new
// ones and add only those that already exist in the Node's internal map
tmp_map.insert(parameters_.begin(), parameters_.end());
// remove explicitly deleted parameters
for (const auto & p : parameters) {
if (p.get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET) {
tmp_map.erase(p.get_name());
// Undeclare parameters that need to be.
for (auto parameter_to_undeclare : parameters_to_be_undeclared) {
auto it = parameters_.find(parameter_to_undeclare->get_name());
// assumption: the parameter to be undeclared should be in the parameter infos map
assert(it != parameters_.end());
if (it != parameters_.end()) {
// Remove it and update the parameter event message.
parameters_.erase(it);
parameter_event_msg.deleted_parameters.push_back(
rclcpp::Parameter(it->first, it->second.value).to_parameter_msg());
}
}
std::swap(tmp_map, parameters_);
// Update the parameter event message for any parameters which were only set,
// and not either declared or undeclared.
for (const auto & parameter : *parameters_to_be_set) {
if (staged_parameter_changes.find(parameter.get_name()) != staged_parameter_changes.end()) {
// This parameter was declared.
continue;
}
auto it = std::find_if(
parameters_to_be_undeclared.begin(),
parameters_to_be_undeclared.end(),
[&parameter](const auto & p) {return p->get_name() == parameter.get_name();});
if (it != parameters_to_be_undeclared.end()) {
// This parameter was undeclared (deleted).
continue;
}
// This parameter was neither declared nor undeclared.
parameter_event_msg.changed_parameters.push_back(parameter.to_parameter_msg());
}
// events_publisher_ may be nullptr if it was disabled in constructor
// Publish if events_publisher_ is not nullptr, which may be if disabled in the constructor.
if (nullptr != events_publisher_) {
parameter_event->stamp = node_clock_->get_clock()->now();
events_publisher_->publish(parameter_event);
parameter_event_msg.stamp = node_clock_->get_clock()->now();
events_publisher_->publish(parameter_event_msg);
}
return result;
@ -251,14 +541,19 @@ NodeParameters::get_parameters(const std::vector<std::string> & names) const
{
std::lock_guard<std::mutex> lock(mutex_);
std::vector<rclcpp::Parameter> results;
results.reserve(names.size());
for (auto & name : names) {
if (std::any_of(parameters_.cbegin(), parameters_.cend(),
[&name](const std::pair<std::string, rclcpp::Parameter> & kv) {
return name == kv.first;
}))
{
results.push_back(parameters_.at(name));
auto found_parameter = parameters_.find(name);
if (found_parameter != parameters_.cend()) {
// found
results.emplace_back(name, found_parameter->second.value);
} else if (this->allow_undeclared_) {
// not found, but undeclared allowed
results.emplace_back(name, rclcpp::ParameterValue());
} else {
// not found, and undeclared are not allowed
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
}
}
return results;
@ -271,8 +566,10 @@ NodeParameters::get_parameter(const std::string & name) const
if (get_parameter(name, parameter)) {
return parameter;
} else if (this->allow_undeclared_) {
return parameter;
} else {
throw std::out_of_range("Parameter '" + name + "' not set");
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
}
}
@ -283,8 +580,12 @@ NodeParameters::get_parameter(
{
std::lock_guard<std::mutex> lock(mutex_);
if (parameters_.count(name)) {
parameter = parameters_.at(name);
auto param_iter = parameters_.find(name);
if (
parameters_.end() != param_iter &&
param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
{
parameter = {name, param_iter->second.value};
return true;
} else {
return false;
@ -296,15 +597,15 @@ NodeParameters::get_parameters_by_prefix(
const std::string & prefix,
std::map<std::string, rclcpp::Parameter> & parameters) const
{
std::string prefix_with_dot = prefix + ".";
bool ret = false;
std::lock_guard<std::mutex> lock(mutex_);
std::string prefix_with_dot = prefix.empty() ? prefix : prefix + ".";
bool ret = false;
for (const auto & param : parameters_) {
if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
// Found one!
parameters[param.first.substr(prefix_with_dot.length())] = param.second;
parameters[param.first.substr(prefix_with_dot.length())] = rclcpp::Parameter(param.second);
ret = true;
}
}
@ -317,17 +618,26 @@ NodeParameters::describe_parameters(const std::vector<std::string> & names) cons
{
std::lock_guard<std::mutex> lock(mutex_);
std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
for (auto & kv : parameters_) {
if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) {
return name == kv.first;
}))
{
rcl_interfaces::msg::ParameterDescriptor parameter_descriptor;
parameter_descriptor.name = kv.first;
parameter_descriptor.type = kv.second.get_type();
results.push_back(parameter_descriptor);
results.reserve(names.size());
for (const auto & name : names) {
auto it = parameters_.find(name);
if (it != parameters_.cend()) {
results.push_back(it->second.descriptor);
} else if (allow_undeclared_) {
// parameter not found, but undeclared allowed, so return empty
rcl_interfaces::msg::ParameterDescriptor default_description;
default_description.name = name;
results.push_back(default_description);
} else {
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
}
}
if (results.size() != names.size()) {
throw std::runtime_error("results and names unexpectedly different sizes");
}
return results;
}
@ -336,16 +646,24 @@ NodeParameters::get_parameter_types(const std::vector<std::string> & names) cons
{
std::lock_guard<std::mutex> lock(mutex_);
std::vector<uint8_t> results;
for (auto & kv : parameters_) {
if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) {
return name == kv.first;
}))
{
results.push_back(kv.second.get_type());
} else {
results.reserve(names.size());
for (const auto & name : names) {
auto it = parameters_.find(name);
if (it != parameters_.cend()) {
results.push_back(it->second.value.get_type());
} else if (allow_undeclared_) {
// parameter not found, but undeclared allowed, so return not set
results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
} else {
throw rclcpp::exceptions::ParameterNotDeclaredException(name);
}
}
if (results.size() != names.size()) {
throw std::runtime_error("results and names unexpectedly different sizes");
}
return results;
}
@ -391,12 +709,39 @@ NodeParameters::list_parameters(const std::vector<std::string> & prefixes, uint6
return result;
}
NodeParameters::OnParametersSetCallbackType
NodeParameters::set_on_parameters_set_callback(OnParametersSetCallbackType callback)
{
auto existing_callback = on_parameters_set_callback_;
on_parameters_set_callback_ = callback;
return existing_callback;
}
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
void
NodeParameters::register_param_change_callback(ParametersCallbackFunction callback)
{
if (parameters_callback_) {
RCUTILS_LOG_WARN("param_change_callback already registered, "
"overwriting previous callback");
if (on_parameters_set_callback_) {
RCLCPP_WARN(
node_logging_->get_logger(),
"on_parameters_set_callback already registered, overwriting previous callback");
}
parameters_callback_ = callback;
on_parameters_set_callback_ = callback;
}
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif
const std::map<std::string, rclcpp::ParameterValue> &
NodeParameters::get_initial_parameter_values() const
{
return initial_parameter_values_;
}

View file

@ -152,54 +152,54 @@ NodeOptions::initial_parameters(const std::vector<rclcpp::Parameter> & initial_p
return *this;
}
const bool &
bool
NodeOptions::use_global_arguments() const
{
return this->node_options_->use_global_arguments;
}
NodeOptions &
NodeOptions::use_global_arguments(const bool & use_global_arguments)
NodeOptions::use_global_arguments(bool use_global_arguments)
{
this->node_options_.reset(); // reset node options to make it be recreated on next access.
this->use_global_arguments_ = use_global_arguments;
return *this;
}
const bool &
bool
NodeOptions::use_intra_process_comms() const
{
return this->use_intra_process_comms_;
}
NodeOptions &
NodeOptions::use_intra_process_comms(const bool & use_intra_process_comms)
NodeOptions::use_intra_process_comms(bool use_intra_process_comms)
{
this->use_intra_process_comms_ = use_intra_process_comms;
return *this;
}
const bool &
bool
NodeOptions::start_parameter_services() const
{
return this->start_parameter_services_;
}
NodeOptions &
NodeOptions::start_parameter_services(const bool & start_parameter_services)
NodeOptions::start_parameter_services(bool start_parameter_services)
{
this->start_parameter_services_ = start_parameter_services;
return *this;
}
const bool &
bool
NodeOptions::start_parameter_event_publisher() const
{
return this->start_parameter_event_publisher_;
}
NodeOptions &
NodeOptions::start_parameter_event_publisher(const bool & start_parameter_event_publisher)
NodeOptions::start_parameter_event_publisher(bool start_parameter_event_publisher)
{
this->start_parameter_event_publisher_ = start_parameter_event_publisher;
return *this;
@ -218,6 +218,33 @@ NodeOptions::parameter_event_qos_profile(const rmw_qos_profile_t & parameter_eve
return *this;
}
bool
NodeOptions::allow_undeclared_parameters() const
{
return this->allow_undeclared_parameters_;
}
NodeOptions &
NodeOptions::allow_undeclared_parameters(bool allow_undeclared_parameters)
{
this->allow_undeclared_parameters_ = allow_undeclared_parameters;
return *this;
}
bool
NodeOptions::automatically_declare_initial_parameters() const
{
return this->automatically_declare_initial_parameters_;
}
NodeOptions &
NodeOptions::automatically_declare_initial_parameters(
bool automatically_declare_initial_parameters)
{
this->automatically_declare_initial_parameters_ = automatically_declare_initial_parameters;
return *this;
}
const rcl_allocator_t &
NodeOptions::allocator() const
{

View file

@ -12,12 +12,24 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#include "rclcpp/parameter.hpp"
#include <ostream>
#include <sstream>
#include <string>
#include <vector>
#include "rclcpp/parameter.hpp"
// When compiling this file, Windows produces a deprecation warning for the
// deprecated function prototype of NodeParameters::register_param_change_callback().
// Other compilers do not.
#if defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
#include "rclcpp/node_interfaces/node_parameters.hpp"
#if defined(_WIN32)
# pragma warning(pop)
#endif
#include "rclcpp/utilities.hpp"
using rclcpp::ParameterType;
@ -28,11 +40,33 @@ Parameter::Parameter()
{
}
Parameter::Parameter(const std::string & name)
: name_(name), value_()
{
}
Parameter::Parameter(const std::string & name, const rclcpp::ParameterValue & value)
: name_(name), value_(value)
{
}
Parameter::Parameter(const rclcpp::node_interfaces::ParameterInfo & parameter_info)
: Parameter(parameter_info.descriptor.name, parameter_info.value)
{
}
bool
Parameter::operator==(const Parameter & rhs) const
{
return this->name_ == rhs.name_ && this->value_ == rhs.value_;
}
bool
Parameter::operator!=(const Parameter & rhs) const
{
return !(*this == rhs);
}
ParameterType
Parameter::get_type() const
{
@ -57,6 +91,12 @@ Parameter::get_value_message() const
return value_.to_value_msg();
}
const rclcpp::ParameterValue &
Parameter::get_parameter_value() const
{
return value_;
}
bool
Parameter::as_bool() const
{

View file

@ -227,3 +227,15 @@ ParameterValue::to_value_msg() const
{
return value_;
}
bool
ParameterValue::operator==(const ParameterValue & rhs) const
{
return this->value_ == rhs.value_;
}
bool
ParameterValue::operator!=(const ParameterValue & rhs) const
{
return this->value_ != rhs.value_;
}

View file

@ -78,20 +78,29 @@ void TimeSource::attachNode(
logger_ = node_logging_->get_logger();
rclcpp::Parameter use_sim_time_param;
if (node_parameters_->get_parameter("use_sim_time", use_sim_time_param)) {
if (use_sim_time_param.get_type() == rclcpp::PARAMETER_BOOL) {
if (use_sim_time_param.get_value<bool>() == true) {
parameter_state_ = SET_TRUE;
enable_ros_time();
create_clock_sub();
}
} else {
RCLCPP_ERROR(logger_, "Invalid type for parameter 'use_sim_time' %s should be bool",
use_sim_time_param.get_type_name().c_str());
// Though this defaults to false, it can be overridden by initial parameter values for the node,
// which may be given by the user at the node's construction or even by command-line arguments.
rclcpp::ParameterValue use_sim_time_param;
const char * use_sim_time_name = "use_sim_time";
if (!node_parameters_->has_parameter(use_sim_time_name)) {
use_sim_time_param = node_parameters_->declare_parameter(
use_sim_time_name,
rclcpp::ParameterValue(false),
rcl_interfaces::msg::ParameterDescriptor());
} else {
use_sim_time_param = node_parameters_->get_parameter(use_sim_time_name).get_parameter_value();
}
if (use_sim_time_param.get_type() == rclcpp::PARAMETER_BOOL) {
if (use_sim_time_param.get<bool>()) {
parameter_state_ = SET_TRUE;
enable_ros_time();
create_clock_sub();
}
} else {
RCLCPP_DEBUG(logger_, "'use_sim_time' parameter not set, using wall time by default.");
// TODO(wjwwood): use set_on_parameters_set_callback to catch the type mismatch,
// before the use_sim_time parameter can ever be set to an invalid value
RCLCPP_ERROR(logger_, "Invalid type '%s' for parameter 'use_sim_time', should be 'bool'",
rclcpp::to_string(use_sim_time_param.get_type()).c_str());
}
// TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609

View file

@ -21,7 +21,9 @@
#include "rclcpp/rclcpp.hpp"
TEST(test_local_parameters, set_parameter_if_not_set) {
auto node = rclcpp::Node::make_shared("test_local_parameters_set_parameter_if_not_set");
auto node = rclcpp::Node::make_shared(
"test_local_parameters_set_parameter_if_not_set",
rclcpp::NodeOptions().allow_undeclared_parameters(true));
{
// try to set a map of parameters
@ -29,7 +31,19 @@ TEST(test_local_parameters, set_parameter_if_not_set) {
{"x", 0.5},
{"y", 1.0},
};
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
node->set_parameters_if_not_set("bar", bar_map);
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif
double bar_x_value;
ASSERT_TRUE(node->get_parameter("bar.x", bar_x_value));
EXPECT_EQ(bar_x_value, 0.5);
@ -51,8 +65,20 @@ TEST(test_local_parameters, set_parameter_if_not_set) {
{
// set parameters for a map with different types, then try to get them back as a map
#if !defined(_WIN32)
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#else // !defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
node->set_parameter_if_not_set("baz.x", 1.0);
node->set_parameter_if_not_set("baz.y", "hello");
#if !defined(_WIN32)
# pragma GCC diagnostic pop
#else // !defined(_WIN32)
# pragma warning(pop)
#endif
std::map<std::string, double> baz_map;
EXPECT_THROW(node->get_parameters("baz", baz_map), rclcpp::ParameterTypeException);
}

File diff suppressed because it is too large Load diff

View file

@ -1,69 +0,0 @@
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <string>
#include <memory>
#include <vector>
#include "rclcpp/node.hpp"
#include "rclcpp/rclcpp.hpp"
class TestNodeWithInitialValues : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, NULL);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
};
TEST_F(TestNodeWithInitialValues, no_initial_values) {
auto options = rclcpp::NodeOptions()
.use_intra_process_comms(false)
.use_global_arguments(false);
auto node = rclcpp::Node::make_shared("node_name", options);
auto list_params_result = node->list_parameters({}, 0);
EXPECT_EQ(0u, list_params_result.names.size());
}
TEST_F(TestNodeWithInitialValues, multiple_initial_values) {
auto parameters = std::vector<rclcpp::Parameter>({
rclcpp::Parameter("foo", true),
rclcpp::Parameter("bar", "hello world"),
rclcpp::Parameter("baz", std::vector<double>{3.14, 2.718})
});
auto options = rclcpp::NodeOptions()
.initial_parameters(parameters)
.use_global_arguments(false)
.use_intra_process_comms(false);
auto node = rclcpp::Node::make_shared("node_name", options);
auto list_params_result = node->list_parameters({}, 0);
EXPECT_EQ(3u, list_params_result.names.size());
EXPECT_TRUE(node->get_parameter("foo").get_value<bool>());
EXPECT_STREQ("hello world", node->get_parameter("bar").get_value<std::string>().c_str());
std::vector<double> double_array = node->get_parameter("baz").get_value<std::vector<double>>();
ASSERT_EQ(2u, double_array.size());
EXPECT_DOUBLE_EQ(3.14, double_array.at(0));
EXPECT_DOUBLE_EQ(2.718, double_array.at(1));
}

View file

@ -234,7 +234,7 @@ TEST_F(TestTimeSource, ROS_time_valid_sim_time) {
ts.attachClock(ros_clock);
EXPECT_FALSE(ros_clock->ros_time_is_active());
node->set_parameter_if_not_set("use_sim_time", true);
set_use_sim_time_parameter(node, rclcpp::ParameterValue(true), ros_clock);
ts.attachNode(node);
EXPECT_TRUE(ros_clock->ros_time_is_active());
@ -465,15 +465,9 @@ TEST_F(TestTimeSource, parameter_activation) {
set_use_sim_time_parameter(node, rclcpp::ParameterValue(true), ros_clock);
EXPECT_TRUE(ros_clock->ros_time_is_active());
set_use_sim_time_parameter(node, rclcpp::ParameterValue(), ros_clock);
EXPECT_TRUE(ros_clock->ros_time_is_active());
set_use_sim_time_parameter(node, rclcpp::ParameterValue(false), ros_clock);
EXPECT_FALSE(ros_clock->ros_time_is_active());
set_use_sim_time_parameter(node, rclcpp::ParameterValue(), ros_clock);
EXPECT_FALSE(ros_clock->ros_time_is_active());
// If the use_sim_time parameter is not explicitly set to True, this clock's use of sim time
// should not be affected by the presence of a clock publisher.
trigger_clock_changes(node, ros_clock, false);

View file

@ -200,7 +200,7 @@ template<typename CallbackT>
void
LifecycleNode::register_param_change_callback(CallbackT && callback)
{
this->node_parameters_->register_param_change_callback(std::forward<CallbackT>(callback));
this->node_parameters_->set_on_parameters_set_callback(std::forward<CallbackT>(callback));
}
template<typename ParameterT>

View file

@ -31,7 +31,17 @@
#include "rclcpp/node_interfaces/node_clock.hpp"
#include "rclcpp/node_interfaces/node_graph.hpp"
#include "rclcpp/node_interfaces/node_logging.hpp"
// When compiling this file, Windows produces a deprecation warning for the
// deprecated function prototype of NodeParameters::register_param_change_callback().
// Other compilers do not.
#if defined(_WIN32)
# pragma warning(push)
# pragma warning(disable: 4996)
#endif
#include "rclcpp/node_interfaces/node_parameters.hpp"
#if defined(_WIN32)
# pragma warning(pop)
#endif
#include "rclcpp/node_interfaces/node_services.hpp"
#include "rclcpp/node_interfaces/node_time_source.hpp"
#include "rclcpp/node_interfaces/node_timers.hpp"
@ -73,6 +83,7 @@ LifecycleNode::LifecycleNode(
)),
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
node_base_,
node_logging_,
node_topics_,
node_services_,
node_clock_,
@ -80,7 +91,9 @@ LifecycleNode::LifecycleNode(
options.use_intra_process_comms(),
options.start_parameter_services(),
options.start_parameter_event_publisher(),
options.parameter_event_qos_profile()
options.parameter_event_qos_profile(),
options.allow_undeclared_parameters(),
options.automatically_declare_initial_parameters()
)),
node_time_source_(new rclcpp::node_interfaces::NodeTimeSource(
node_base_,