Skip to content

Commit

Permalink
Add missing template functionality to lifecycle_node. (#707)
Browse files Browse the repository at this point in the history
* Add missing template functionality to lifecycle_node.

Recent changes to the node_parameters interface was accompanied by additions to the
node.hpp header and implementation files. However, these additions were not also made
to the corresponding lifecycle node files. This PR includes the changes required for
the lifecycle node.

Going forward, I suggest that any code like this that supplements the basic node interfaces
should either be factored out into a separate header that both node and lifecycle_node
include, or that the supplemental code simply be included in the appropriate node_interface
file directly, if possible. That way we can avoid code duplication and its symptoms which
is node and lifecycle_node getting out of sync (which they have several times).

Signed-off-by: Michael Jeronimo <michael.jeronimo@intel.com>

* consolidate documentation to just be in rclcpp/node.hpp

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

* fix visibility macros

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

* deprecation methods that were also deprecated in rclcpp::Node

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

* fixup variable name

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

* add missing template method implementations

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

* add more methods that were not ported to lifecycle node originally

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

* fix cpplint

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
Michael Jeronimo authored and wjwwood committed May 15, 2019
1 parent b17bbf3 commit 1081e75
Show file tree
Hide file tree
Showing 4 changed files with 267 additions and 41 deletions.
1 change: 0 additions & 1 deletion rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -940,7 +940,6 @@ class Node : public std::enable_shared_from_this<Node>
void
register_param_change_callback(CallbackT && callback);


/// Get the fully-qualified names of all available nodes.
/**
* The fully-qualified name includes the local namespace and name of the node.
Expand Down
198 changes: 161 additions & 37 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,11 @@
#ifndef RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_
#define RCLCPP_LIFECYCLE__LIFECYCLE_NODE_HPP_

#include <string>
#include <map>
#include <vector>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "rcl/error_handling.h"
#include "rcl/node.h"
Expand Down Expand Up @@ -333,113 +334,236 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
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.
/**
* \sa rclcpp::Node::declare_parameter
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::declare_parameter
*/
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.
/**
* \sa rclcpp::Node::declare_parameters
*/
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.
/**
* \sa rclcpp::Node::declare_parameters
*/
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.
/**
* \sa rclcpp::Node::undeclare_parameter
*/
RCLCPP_LIFECYCLE_PUBLIC
void
undeclare_parameter(const std::string & name);

/// Return true if a given parameter is declared.
/**
* \sa rclcpp::Node::has_parameter
*/
RCLCPP_LIFECYCLE_PUBLIC
bool
has_parameter(const std::string & name) const;

/// Set a single parameter.
/**
* \sa rclcpp::Node::set_parameter
*/
RCLCPP_LIFECYCLE_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameter(const rclcpp::Parameter & parameter);

/// Set one or more parameters, one at a time.
/**
* \sa rclcpp::Node::set_parameters
*/
RCLCPP_LIFECYCLE_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::Parameter> & parameters);

/// Set one or more parameters, all at once.
/**
* \sa rclcpp::Node::set_parameters_atomically
*/
RCLCPP_LIFECYCLE_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);

/// Set one parameter, unless that parameter has already been set.
/**
* \sa rclcpp::Node::set_parameter_if_not_set
*/
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 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.
*
* \param[in] name The prefix of the parameters to set.
* \param[in] values The parameters to set in the given prefix.
* \sa rclcpp::Node::set_parameters_if_not_set
*/
template<typename MapValueT>
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
[[deprecated("use declare_parameters() instead")]]
void
set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, MapValueT> & values);

RCLCPP_LIFECYCLE_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;

/// Return the parameter by the given name.
/**
* \sa rclcpp::Node::get_parameter
*/
RCLCPP_LIFECYCLE_PUBLIC
rclcpp::Parameter
get_parameter(const std::string & name) const;

/// Get the value of a parameter by the given name, and return true if it was set.
/**
* \sa rclcpp::Node::get_parameter
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::get_parameter
*/
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
* \sa rclcpp::Node::get_parameter_or
*/
template<typename MapValueT>
bool
get_parameters(
const std::string & name,
std::map<std::string, MapValueT> & values) const;

template<typename ParameterT>
bool
get_parameter_or(
const std::string & name,
ParameterT & value,
const ParameterT & alternative_value) const;

/// Return the parameters by the given parameter names.
/**
* \sa rclcpp::Node::get_parameters
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::get_parameters
*/
template<typename MapValueT>
bool
get_parameters(
const std::string & prefix,
std::map<std::string, MapValueT> & 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
* in the parameter.
* 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.
*
* \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.
* \sa rclcpp::Node::get_parameter_or_set
*/
template<typename ParameterT>
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
[[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.
/**
* \sa rclcpp::Node::describe_parameter
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::describe_parameters
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::get_parameter_types
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::list_parameters
*/
RCLCPP_LIFECYCLE_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.
/**
* \sa rclcpp::Node::set_on_parameters_set_callback
*/
RCLCPP_LIFECYCLE_PUBLIC
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType
set_on_parameters_set_callback(
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback);

/// Register the callback for parameter changes
/**
* \param[in] callback User defined function which is expected to atomically set parameters.
* \note Repeated invocations of this function will overwrite previous callbacks
* \sa rclcpp::Node::register_param_change_callback
*/
template<typename CallbackT>
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
[[deprecated("use set_on_parameters_set_callback() instead")]]
void
register_param_change_callback(CallbackT && callback);

Expand Down
60 changes: 58 additions & 2 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,6 +223,62 @@ LifecycleNode::create_service(
service_name, std::forward<CallbackT>(callback), qos_profile, group);
}

template<typename ParameterT>
auto
LifecycleNode::declare_parameter(
const std::string & name,
const ParameterT & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor)
{
return this->declare_parameter(
name,
rclcpp::ParameterValue(default_value),
parameter_descriptor
).get<ParameterT>();
}

template<typename ParameterT>
std::vector<ParameterT>
LifecycleNode::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>
LifecycleNode::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>
bool
LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) const
Expand Down Expand Up @@ -283,11 +339,11 @@ LifecycleNode::set_parameters_if_not_set(
template<typename MapValueT>
bool
LifecycleNode::get_parameters(
const std::string & name,
const std::string & prefix,
std::map<std::string, MapValueT> & values) const
{
std::map<std::string, rclcpp::Parameter> params;
bool result = node_parameters_->get_parameters_by_prefix(name, params);
bool result = node_parameters_->get_parameters_by_prefix(prefix, params);
if (result) {
for (const auto & param : params) {
values[param.first] = param.second.get_value<MapValueT>();
Expand Down
Loading

0 comments on commit 1081e75

Please sign in to comment.