Merge pull request #36 from ros2/refactor_msg_gen
refactor message generation
This commit is contained in:
		
						commit
						43c0013069
					
				
					 5 changed files with 125 additions and 128 deletions
				
			
		| 
						 | 
					@ -20,6 +20,10 @@
 | 
				
			||||||
#include <string>
 | 
					#include <string>
 | 
				
			||||||
#include <tuple>
 | 
					#include <tuple>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include <rcl_interfaces/msg/list_parameters_result.hpp>
 | 
				
			||||||
 | 
					#include <rcl_interfaces/msg/parameter_descriptor.hpp>
 | 
				
			||||||
 | 
					#include <rcl_interfaces/msg/set_parameters_result.hpp>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <rclcpp/callback_group.hpp>
 | 
					#include <rclcpp/callback_group.hpp>
 | 
				
			||||||
#include <rclcpp/client.hpp>
 | 
					#include <rclcpp/client.hpp>
 | 
				
			||||||
#include <rclcpp/context.hpp>
 | 
					#include <rclcpp/context.hpp>
 | 
				
			||||||
| 
						 | 
					@ -148,22 +152,22 @@ public:
 | 
				
			||||||
    FunctorT callback,
 | 
					    FunctorT callback,
 | 
				
			||||||
    rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
 | 
					    rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::vector<rcl_interfaces::SetParametersResult> set_parameters(
 | 
					  std::vector<rcl_interfaces::msg::SetParametersResult> set_parameters(
 | 
				
			||||||
    const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
 | 
					    const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  rcl_interfaces::SetParametersResult set_parameters_atomically(
 | 
					  rcl_interfaces::msg::SetParametersResult set_parameters_atomically(
 | 
				
			||||||
    const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
 | 
					    const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::vector<rclcpp::parameter::ParameterVariant> get_parameters(
 | 
					  std::vector<rclcpp::parameter::ParameterVariant> get_parameters(
 | 
				
			||||||
    const std::vector<std::string> & names) const;
 | 
					    const std::vector<std::string> & names) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::vector<rcl_interfaces::ParameterDescriptor> describe_parameters(
 | 
					  std::vector<rcl_interfaces::msg::ParameterDescriptor> describe_parameters(
 | 
				
			||||||
    const std::vector<std::string> & names) const;
 | 
					    const std::vector<std::string> & names) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::vector<uint8_t> get_parameter_types(
 | 
					  std::vector<uint8_t> get_parameter_types(
 | 
				
			||||||
    const std::vector<std::string> & names) const;
 | 
					    const std::vector<std::string> & names) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  rcl_interfaces::ListParametersResult list_parameters(
 | 
					  rcl_interfaces::msg::ListParametersResult list_parameters(
 | 
				
			||||||
    const std::vector<std::string> & prefixes, uint64_t depth) const;
 | 
					    const std::vector<std::string> & prefixes, uint64_t depth) const;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
private:
 | 
					private:
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -213,15 +213,15 @@ Node::create_service(
 | 
				
			||||||
  return serv;
 | 
					  return serv;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
std::vector<rcl_interfaces::SetParametersResult>
 | 
					std::vector<rcl_interfaces::msg::SetParametersResult>
 | 
				
			||||||
Node::set_parameters(
 | 
					Node::set_parameters(
 | 
				
			||||||
  const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
 | 
					  const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  std::lock_guard<std::mutex> lock(mutex_);
 | 
					  std::lock_guard<std::mutex> lock(mutex_);
 | 
				
			||||||
  std::vector<rcl_interfaces::SetParametersResult> results;
 | 
					  std::vector<rcl_interfaces::msg::SetParametersResult> results;
 | 
				
			||||||
  for (auto p : parameters) {
 | 
					  for (auto p : parameters) {
 | 
				
			||||||
    parameters_[p.get_name()] = p;
 | 
					    parameters_[p.get_name()] = p;
 | 
				
			||||||
    rcl_interfaces::SetParametersResult result;
 | 
					    rcl_interfaces::msg::SetParametersResult result;
 | 
				
			||||||
    result.successful = true;
 | 
					    result.successful = true;
 | 
				
			||||||
    // TODO: handle parameter constraints
 | 
					    // TODO: handle parameter constraints
 | 
				
			||||||
    results.push_back(result);
 | 
					    results.push_back(result);
 | 
				
			||||||
| 
						 | 
					@ -229,7 +229,7 @@ Node::set_parameters(
 | 
				
			||||||
  return results;
 | 
					  return results;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
rcl_interfaces::SetParametersResult
 | 
					rcl_interfaces::msg::SetParametersResult
 | 
				
			||||||
Node::set_parameters_atomically(
 | 
					Node::set_parameters_atomically(
 | 
				
			||||||
  const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
 | 
					  const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -241,7 +241,7 @@ Node::set_parameters_atomically(
 | 
				
			||||||
  tmp_map.insert(parameters_.begin(), parameters_.end());
 | 
					  tmp_map.insert(parameters_.begin(), parameters_.end());
 | 
				
			||||||
  std::swap(tmp_map, parameters_);
 | 
					  std::swap(tmp_map, parameters_);
 | 
				
			||||||
  // TODO: handle parameter constraints
 | 
					  // TODO: handle parameter constraints
 | 
				
			||||||
  rcl_interfaces::SetParametersResult result;
 | 
					  rcl_interfaces::msg::SetParametersResult result;
 | 
				
			||||||
  result.successful = true;
 | 
					  result.successful = true;
 | 
				
			||||||
  return result;
 | 
					  return result;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
| 
						 | 
					@ -263,18 +263,18 @@ Node::get_parameters(
 | 
				
			||||||
  return results;
 | 
					  return results;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
std::vector<rcl_interfaces::ParameterDescriptor>
 | 
					std::vector<rcl_interfaces::msg::ParameterDescriptor>
 | 
				
			||||||
Node::describe_parameters(
 | 
					Node::describe_parameters(
 | 
				
			||||||
  const std::vector<std::string> & names) const
 | 
					  const std::vector<std::string> & names) const
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  std::lock_guard<std::mutex> lock(mutex_);
 | 
					  std::lock_guard<std::mutex> lock(mutex_);
 | 
				
			||||||
  std::vector<rcl_interfaces::ParameterDescriptor> results;
 | 
					  std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
 | 
				
			||||||
  for (auto & kv : parameters_) {
 | 
					  for (auto & kv : parameters_) {
 | 
				
			||||||
    if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) {
 | 
					    if (std::any_of(names.cbegin(), names.cend(), [&kv](const std::string & name) {
 | 
				
			||||||
      return name == kv.first;
 | 
					      return name == kv.first;
 | 
				
			||||||
    }))
 | 
					    }))
 | 
				
			||||||
    {
 | 
					    {
 | 
				
			||||||
      rcl_interfaces::ParameterDescriptor parameter_descriptor;
 | 
					      rcl_interfaces::msg::ParameterDescriptor parameter_descriptor;
 | 
				
			||||||
      parameter_descriptor.name = kv.first;
 | 
					      parameter_descriptor.name = kv.first;
 | 
				
			||||||
      parameter_descriptor.parameter_type = kv.second.get_type();
 | 
					      parameter_descriptor.parameter_type = kv.second.get_type();
 | 
				
			||||||
      results.push_back(parameter_descriptor);
 | 
					      results.push_back(parameter_descriptor);
 | 
				
			||||||
| 
						 | 
					@ -296,18 +296,18 @@ Node::get_parameter_types(
 | 
				
			||||||
    {
 | 
					    {
 | 
				
			||||||
      results.push_back(kv.second.get_type());
 | 
					      results.push_back(kv.second.get_type());
 | 
				
			||||||
    } else {
 | 
					    } else {
 | 
				
			||||||
      results.push_back(rcl_interfaces::ParameterType::PARAMETER_NOT_SET);
 | 
					      results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  return results;
 | 
					  return results;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
rcl_interfaces::ListParametersResult
 | 
					rcl_interfaces::msg::ListParametersResult
 | 
				
			||||||
Node::list_parameters(
 | 
					Node::list_parameters(
 | 
				
			||||||
  const std::vector<std::string> & prefixes, uint64_t depth) const
 | 
					  const std::vector<std::string> & prefixes, uint64_t depth) const
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  std::lock_guard<std::mutex> lock(mutex_);
 | 
					  std::lock_guard<std::mutex> lock(mutex_);
 | 
				
			||||||
  rcl_interfaces::ListParametersResult result;
 | 
					  rcl_interfaces::msg::ListParametersResult result;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // TODO(esteve): define parameter separator, use "." for now
 | 
					  // TODO(esteve): define parameter separator, use "." for now
 | 
				
			||||||
  for (auto & kv : parameters_) {
 | 
					  for (auto & kv : parameters_) {
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -19,15 +19,9 @@
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <rmw/rmw.h>
 | 
					#include <rmw/rmw.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <rcl_interfaces/GetParameters.h>
 | 
					#include <rcl_interfaces/msg/parameter.hpp>
 | 
				
			||||||
#include <rcl_interfaces/GetParameterTypes.h>
 | 
					#include <rcl_interfaces/msg/parameter_type.hpp>
 | 
				
			||||||
#include <rcl_interfaces/Parameter.h>
 | 
					#include <rcl_interfaces/msg/parameter_value.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ParameterDescriptor.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/ParameterType.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/SetParameters.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/SetParametersAtomically.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/ListParameters.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/DescribeParameters.h>
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
namespace rclcpp
 | 
					namespace rclcpp
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -37,12 +31,12 @@ namespace parameter
 | 
				
			||||||
 | 
					
 | 
				
			||||||
enum ParameterType
 | 
					enum ParameterType
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
  PARAMETER_NOT_SET=rcl_interfaces::ParameterType::PARAMETER_NOT_SET,
 | 
					  PARAMETER_NOT_SET=rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
 | 
				
			||||||
  PARAMETER_BOOL=rcl_interfaces::ParameterType::PARAMETER_BOOL,
 | 
					  PARAMETER_BOOL=rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
 | 
				
			||||||
  PARAMETER_INTEGER=rcl_interfaces::ParameterType::PARAMETER_INTEGER,
 | 
					  PARAMETER_INTEGER=rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER,
 | 
				
			||||||
  PARAMETER_DOUBLE=rcl_interfaces::ParameterType::PARAMETER_DOUBLE,
 | 
					  PARAMETER_DOUBLE=rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
 | 
				
			||||||
  PARAMETER_STRING=rcl_interfaces::ParameterType::PARAMETER_STRING,
 | 
					  PARAMETER_STRING=rcl_interfaces::msg::ParameterType::PARAMETER_STRING,
 | 
				
			||||||
  PARAMETER_BYTES=rcl_interfaces::ParameterType::PARAMETER_BYTES,
 | 
					  PARAMETER_BYTES=rcl_interfaces::msg::ParameterType::PARAMETER_BYTES,
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// Structure to store an arbitrary parameter with templated get/set methods
 | 
					// Structure to store an arbitrary parameter with templated get/set methods
 | 
				
			||||||
| 
						 | 
					@ -52,56 +46,56 @@ public:
 | 
				
			||||||
  ParameterVariant()
 | 
					  ParameterVariant()
 | 
				
			||||||
  : name_("")
 | 
					  : name_("")
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_NOT_SET;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const bool bool_value)
 | 
					  explicit ParameterVariant(const std::string & name, const bool bool_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.bool_value = bool_value;
 | 
					    value_.bool_value = bool_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_BOOL;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const int int_value)
 | 
					  explicit ParameterVariant(const std::string & name, const int int_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.integer_value = int_value;
 | 
					    value_.integer_value = int_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_INTEGER;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const int64_t int_value)
 | 
					  explicit ParameterVariant(const std::string & name, const int64_t int_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.integer_value = int_value;
 | 
					    value_.integer_value = int_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_INTEGER;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const float double_value)
 | 
					  explicit ParameterVariant(const std::string & name, const float double_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.double_value = double_value;
 | 
					    value_.double_value = double_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_DOUBLE;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const double double_value)
 | 
					  explicit ParameterVariant(const std::string & name, const double double_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.double_value = double_value;
 | 
					    value_.double_value = double_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_DOUBLE;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const std::string & string_value)
 | 
					  explicit ParameterVariant(const std::string & name, const std::string & string_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.string_value = string_value;
 | 
					    value_.string_value = string_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_STRING;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
  explicit ParameterVariant(const std::string & name, const std::vector<uint8_t> & bytes_value)
 | 
					  explicit ParameterVariant(const std::string & name, const std::vector<uint8_t> & bytes_value)
 | 
				
			||||||
  : name_(name)
 | 
					  : name_(name)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    value_.bytes_value = bytes_value;
 | 
					    value_.bytes_value = bytes_value;
 | 
				
			||||||
    value_.parameter_type = rcl_interfaces::ParameterType::PARAMETER_BYTES;
 | 
					    value_.parameter_type = rcl_interfaces::msg::ParameterType::PARAMETER_BYTES;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  inline ParameterType get_type() const {return static_cast<ParameterType>(value_.parameter_type); }
 | 
					  inline ParameterType get_type() const {return static_cast<ParameterType>(value_.parameter_type); }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  inline std::string get_name() const & {return name_; }
 | 
					  inline std::string get_name() const & {return name_; }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  inline rcl_interfaces::ParameterValue get_parameter_value() const
 | 
					  inline rcl_interfaces::msg::ParameterValue get_parameter_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    return value_;
 | 
					    return value_;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
| 
						 | 
					@ -110,7 +104,7 @@ public:
 | 
				
			||||||
  typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
 | 
					  typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
 | 
				
			||||||
  get_value() const
 | 
					  get_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_INTEGER) {
 | 
					    if (value_.parameter_type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
 | 
				
			||||||
      // TODO: use custom exception
 | 
					      // TODO: use custom exception
 | 
				
			||||||
      throw std::runtime_error("Invalid type");
 | 
					      throw std::runtime_error("Invalid type");
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
| 
						 | 
					@ -120,7 +114,7 @@ public:
 | 
				
			||||||
  typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::type
 | 
					  typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::type
 | 
				
			||||||
  get_value() const
 | 
					  get_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_DOUBLE) {
 | 
					    if (value_.parameter_type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
 | 
				
			||||||
      // TODO: use custom exception
 | 
					      // TODO: use custom exception
 | 
				
			||||||
      throw std::runtime_error("Invalid type");
 | 
					      throw std::runtime_error("Invalid type");
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
| 
						 | 
					@ -130,7 +124,7 @@ public:
 | 
				
			||||||
  typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
 | 
					  typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
 | 
				
			||||||
  get_value() const
 | 
					  get_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_STRING) {
 | 
					    if (value_.parameter_type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) {
 | 
				
			||||||
      // TODO: use custom exception
 | 
					      // TODO: use custom exception
 | 
				
			||||||
      throw std::runtime_error("Invalid type");
 | 
					      throw std::runtime_error("Invalid type");
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
| 
						 | 
					@ -140,7 +134,7 @@ public:
 | 
				
			||||||
  typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
 | 
					  typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
 | 
				
			||||||
  get_value() const
 | 
					  get_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_BOOL) {
 | 
					    if (value_.parameter_type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
 | 
				
			||||||
      // TODO: use custom exception
 | 
					      // TODO: use custom exception
 | 
				
			||||||
      throw std::runtime_error("Invalid type");
 | 
					      throw std::runtime_error("Invalid type");
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
| 
						 | 
					@ -151,7 +145,7 @@ public:
 | 
				
			||||||
  const std::vector<uint8_t> &>::type
 | 
					  const std::vector<uint8_t> &>::type
 | 
				
			||||||
  get_value() const
 | 
					  get_value() const
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    if (value_.parameter_type != rcl_interfaces::ParameterType::PARAMETER_BYTES) {
 | 
					    if (value_.parameter_type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTES) {
 | 
				
			||||||
      // TODO: use custom exception
 | 
					      // TODO: use custom exception
 | 
				
			||||||
      throw std::runtime_error("Invalid type");
 | 
					      throw std::runtime_error("Invalid type");
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
| 
						 | 
					@ -171,7 +165,7 @@ public:
 | 
				
			||||||
    return get_value<ParameterType::PARAMETER_BYTES>();
 | 
					    return get_value<ParameterType::PARAMETER_BYTES>();
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  static ParameterVariant from_parameter(const rcl_interfaces::Parameter & parameter)
 | 
					  static ParameterVariant from_parameter(const rcl_interfaces::msg::Parameter & parameter)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    switch (parameter.value.parameter_type) {
 | 
					    switch (parameter.value.parameter_type) {
 | 
				
			||||||
      case PARAMETER_BOOL:
 | 
					      case PARAMETER_BOOL:
 | 
				
			||||||
| 
						 | 
					@ -191,9 +185,9 @@ public:
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  rcl_interfaces::Parameter to_parameter()
 | 
					  rcl_interfaces::msg::Parameter to_parameter()
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    rcl_interfaces::Parameter parameter;
 | 
					    rcl_interfaces::msg::Parameter parameter;
 | 
				
			||||||
    parameter.name = name_;
 | 
					    parameter.name = name_;
 | 
				
			||||||
    parameter.value = value_;
 | 
					    parameter.value = value_;
 | 
				
			||||||
    return parameter;
 | 
					    return parameter;
 | 
				
			||||||
| 
						 | 
					@ -201,7 +195,7 @@ public:
 | 
				
			||||||
 | 
					
 | 
				
			||||||
private:
 | 
					private:
 | 
				
			||||||
  std::string name_;
 | 
					  std::string name_;
 | 
				
			||||||
  rcl_interfaces::ParameterValue value_;
 | 
					  rcl_interfaces::msg::ParameterValue value_;
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
} /* namespace parameter */
 | 
					} /* namespace parameter */
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -24,15 +24,14 @@
 | 
				
			||||||
#include <rclcpp/node.hpp>
 | 
					#include <rclcpp/node.hpp>
 | 
				
			||||||
#include <rclcpp/parameter.hpp>
 | 
					#include <rclcpp/parameter.hpp>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <rcl_interfaces/GetParameters.h>
 | 
					#include <rcl_interfaces/msg/parameter.hpp>
 | 
				
			||||||
#include <rcl_interfaces/GetParameterTypes.h>
 | 
					#include <rcl_interfaces/msg/parameter_value.hpp>
 | 
				
			||||||
#include <rcl_interfaces/Parameter.h>
 | 
					#include <rcl_interfaces/srv/describe_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ParameterDescriptor.h>
 | 
					#include <rcl_interfaces/srv/get_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ParameterType.h>
 | 
					#include <rcl_interfaces/srv/get_parameter_types.hpp>
 | 
				
			||||||
#include <rcl_interfaces/SetParameters.h>
 | 
					#include <rcl_interfaces/srv/list_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/SetParametersAtomically.h>
 | 
					#include <rcl_interfaces/srv/set_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ListParameters.h>
 | 
					#include <rcl_interfaces/srv/set_parameters_atomically.hpp>
 | 
				
			||||||
#include <rcl_interfaces/DescribeParameters.h>
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
namespace rclcpp
 | 
					namespace rclcpp
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -55,15 +54,15 @@ public:
 | 
				
			||||||
    } else {
 | 
					    } else {
 | 
				
			||||||
      remote_node_name_ = node_->get_name();
 | 
					      remote_node_name_ = node_->get_name();
 | 
				
			||||||
    }
 | 
					    }
 | 
				
			||||||
    get_parameters_client_ = node_->create_client<rcl_interfaces::GetParameters>(
 | 
					    get_parameters_client_ = node_->create_client<rcl_interfaces::srv::GetParameters>(
 | 
				
			||||||
      remote_node_name_ + "__get_parameters");
 | 
					      remote_node_name_ + "__get_parameters");
 | 
				
			||||||
    get_parameter_types_client_ = node_->create_client<rcl_interfaces::GetParameterTypes>(
 | 
					    get_parameter_types_client_ = node_->create_client<rcl_interfaces::srv::GetParameterTypes>(
 | 
				
			||||||
      remote_node_name_ + "__get_parameter_types");
 | 
					      remote_node_name_ + "__get_parameter_types");
 | 
				
			||||||
    set_parameters_client_ = node_->create_client<rcl_interfaces::SetParameters>(
 | 
					    set_parameters_client_ = node_->create_client<rcl_interfaces::srv::SetParameters>(
 | 
				
			||||||
      remote_node_name_ + "__set_parameters");
 | 
					      remote_node_name_ + "__set_parameters");
 | 
				
			||||||
    list_parameters_client_ = node_->create_client<rcl_interfaces::ListParameters>(
 | 
					    list_parameters_client_ = node_->create_client<rcl_interfaces::srv::ListParameters>(
 | 
				
			||||||
      remote_node_name_ + "__list_parameters");
 | 
					      remote_node_name_ + "__list_parameters");
 | 
				
			||||||
    describe_parameters_client_ = node_->create_client<rcl_interfaces::DescribeParameters>(
 | 
					    describe_parameters_client_ = node_->create_client<rcl_interfaces::srv::DescribeParameters>(
 | 
				
			||||||
      remote_node_name_ + "__describe_parameters");
 | 
					      remote_node_name_ + "__describe_parameters");
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					@ -76,20 +75,20 @@ public:
 | 
				
			||||||
    std::promise<std::vector<rclcpp::parameter::ParameterVariant>> promise_result;
 | 
					    std::promise<std::vector<rclcpp::parameter::ParameterVariant>> promise_result;
 | 
				
			||||||
    auto future_result = promise_result.get_future().share();
 | 
					    auto future_result = promise_result.get_future().share();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    auto request = std::make_shared<rcl_interfaces::GetParameters::Request>();
 | 
					    auto request = std::make_shared<rcl_interfaces::srv::GetParameters::Request>();
 | 
				
			||||||
    request->names = names;
 | 
					    request->names = names;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    get_parameters_client_->async_send_request(
 | 
					    get_parameters_client_->async_send_request(
 | 
				
			||||||
      request,
 | 
					      request,
 | 
				
			||||||
      [&names, &promise_result, &future_result, &callback](
 | 
					      [&names, &promise_result, &future_result, &callback](
 | 
				
			||||||
        rclcpp::client::Client<rcl_interfaces::GetParameters>::SharedFuture cb_f) {
 | 
					        rclcpp::client::Client<rcl_interfaces::srv::GetParameters>::SharedFuture cb_f) {
 | 
				
			||||||
          std::vector<rclcpp::parameter::ParameterVariant> parameter_variants;
 | 
					          std::vector<rclcpp::parameter::ParameterVariant> parameter_variants;
 | 
				
			||||||
          auto & pvalues = cb_f.get()->values;
 | 
					          auto & pvalues = cb_f.get()->values;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
          std::transform(pvalues.begin(), pvalues.end(), std::back_inserter(parameter_variants),
 | 
					          std::transform(pvalues.begin(), pvalues.end(), std::back_inserter(parameter_variants),
 | 
				
			||||||
          [&names, &pvalues](rcl_interfaces::ParameterValue pvalue) {
 | 
					          [&names, &pvalues](rcl_interfaces::msg::ParameterValue pvalue) {
 | 
				
			||||||
            auto i = &pvalue - &pvalues[0];
 | 
					            auto i = &pvalue - &pvalues[0];
 | 
				
			||||||
            rcl_interfaces::Parameter parameter;
 | 
					            rcl_interfaces::msg::Parameter parameter;
 | 
				
			||||||
            parameter.name = names[i];
 | 
					            parameter.name = names[i];
 | 
				
			||||||
            parameter.value = pvalue;
 | 
					            parameter.value = pvalue;
 | 
				
			||||||
            return rclcpp::parameter::ParameterVariant::from_parameter(parameter);
 | 
					            return rclcpp::parameter::ParameterVariant::from_parameter(parameter);
 | 
				
			||||||
| 
						 | 
					@ -113,13 +112,13 @@ public:
 | 
				
			||||||
    std::promise<std::vector<rclcpp::parameter::ParameterType>> promise_result;
 | 
					    std::promise<std::vector<rclcpp::parameter::ParameterType>> promise_result;
 | 
				
			||||||
    auto future_result = promise_result.get_future().share();
 | 
					    auto future_result = promise_result.get_future().share();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    auto request = std::make_shared<rcl_interfaces::GetParameterTypes::Request>();
 | 
					    auto request = std::make_shared<rcl_interfaces::srv::GetParameterTypes::Request>();
 | 
				
			||||||
    request->parameter_names = parameter_names;
 | 
					    request->parameter_names = parameter_names;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    get_parameter_types_client_->async_send_request(
 | 
					    get_parameter_types_client_->async_send_request(
 | 
				
			||||||
      request,
 | 
					      request,
 | 
				
			||||||
      [&promise_result, &future_result, &callback](
 | 
					      [&promise_result, &future_result, &callback](
 | 
				
			||||||
        rclcpp::client::Client<rcl_interfaces::GetParameterTypes>::SharedFuture cb_f) {
 | 
					        rclcpp::client::Client<rcl_interfaces::srv::GetParameterTypes>::SharedFuture cb_f) {
 | 
				
			||||||
          std::vector<rclcpp::parameter::ParameterType> parameter_types;
 | 
					          std::vector<rclcpp::parameter::ParameterType> parameter_types;
 | 
				
			||||||
          auto & pts = cb_f.get()->parameter_types;
 | 
					          auto & pts = cb_f.get()->parameter_types;
 | 
				
			||||||
          std::transform(pts.begin(), pts.end(), std::back_inserter(parameter_types),
 | 
					          std::transform(pts.begin(), pts.end(), std::back_inserter(parameter_types),
 | 
				
			||||||
| 
						 | 
					@ -134,16 +133,17 @@ public:
 | 
				
			||||||
    return future_result;
 | 
					    return future_result;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>
 | 
					  std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
 | 
				
			||||||
  set_parameters(
 | 
					  set_parameters(
 | 
				
			||||||
    std::vector<rclcpp::parameter::ParameterVariant> parameters,
 | 
					    std::vector<rclcpp::parameter::ParameterVariant> parameters,
 | 
				
			||||||
    std::function<void(
 | 
					    std::function<
 | 
				
			||||||
      std::shared_future<std::vector<rcl_interfaces::SetParametersResult>>)> callback = nullptr)
 | 
					      void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
 | 
				
			||||||
 | 
					    > callback = nullptr)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    std::promise<std::vector<rcl_interfaces::SetParametersResult>> promise_result;
 | 
					    std::promise<std::vector<rcl_interfaces::msg::SetParametersResult>> promise_result;
 | 
				
			||||||
    auto future_result = promise_result.get_future().share();
 | 
					    auto future_result = promise_result.get_future().share();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    auto request = std::make_shared<rcl_interfaces::SetParameters::Request>();
 | 
					    auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    std::transform(parameters.begin(), parameters.end(), std::back_inserter(
 | 
					    std::transform(parameters.begin(), parameters.end(), std::back_inserter(
 | 
				
			||||||
        request->parameters), [](
 | 
					        request->parameters), [](
 | 
				
			||||||
| 
						 | 
					@ -152,7 +152,7 @@ public:
 | 
				
			||||||
    set_parameters_client_->async_send_request(
 | 
					    set_parameters_client_->async_send_request(
 | 
				
			||||||
      request,
 | 
					      request,
 | 
				
			||||||
      [&promise_result, &future_result, &callback](
 | 
					      [&promise_result, &future_result, &callback](
 | 
				
			||||||
        rclcpp::client::Client<rcl_interfaces::SetParameters>::SharedFuture cb_f) {
 | 
					        rclcpp::client::Client<rcl_interfaces::srv::SetParameters>::SharedFuture cb_f) {
 | 
				
			||||||
          promise_result.set_value(cb_f.get()->results);
 | 
					          promise_result.set_value(cb_f.get()->results);
 | 
				
			||||||
          if (callback != nullptr) {
 | 
					          if (callback != nullptr) {
 | 
				
			||||||
            callback(future_result);
 | 
					            callback(future_result);
 | 
				
			||||||
| 
						 | 
					@ -163,16 +163,16 @@ public:
 | 
				
			||||||
    return future_result;
 | 
					    return future_result;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::shared_future<rcl_interfaces::SetParametersResult>
 | 
					  std::shared_future<rcl_interfaces::msg::SetParametersResult>
 | 
				
			||||||
  set_parameters_atomically(
 | 
					  set_parameters_atomically(
 | 
				
			||||||
    std::vector<rclcpp::parameter::ParameterVariant> parameters,
 | 
					    std::vector<rclcpp::parameter::ParameterVariant> parameters,
 | 
				
			||||||
    std::function<void(
 | 
					    std::function<void(
 | 
				
			||||||
      std::shared_future<rcl_interfaces::SetParametersResult>)> callback = nullptr)
 | 
					      std::shared_future<rcl_interfaces::msg::SetParametersResult>)> callback = nullptr)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    std::promise<rcl_interfaces::SetParametersResult> promise_result;
 | 
					    std::promise<rcl_interfaces::msg::SetParametersResult> promise_result;
 | 
				
			||||||
    auto future_result = promise_result.get_future().share();
 | 
					    auto future_result = promise_result.get_future().share();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    auto request = std::make_shared<rcl_interfaces::SetParametersAtomically::Request>();
 | 
					    auto request = std::make_shared<rcl_interfaces::srv::SetParametersAtomically::Request>();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    std::transform(parameters.begin(), parameters.end(), std::back_inserter(
 | 
					    std::transform(parameters.begin(), parameters.end(), std::back_inserter(
 | 
				
			||||||
        request->parameters), [](
 | 
					        request->parameters), [](
 | 
				
			||||||
| 
						 | 
					@ -181,7 +181,7 @@ public:
 | 
				
			||||||
    set_parameters_atomically_client_->async_send_request(
 | 
					    set_parameters_atomically_client_->async_send_request(
 | 
				
			||||||
      request,
 | 
					      request,
 | 
				
			||||||
      [&promise_result, &future_result, &callback](
 | 
					      [&promise_result, &future_result, &callback](
 | 
				
			||||||
        rclcpp::client::Client<rcl_interfaces::SetParametersAtomically>::SharedFuture cb_f) {
 | 
					        rclcpp::client::Client<rcl_interfaces::srv::SetParametersAtomically>::SharedFuture cb_f) {
 | 
				
			||||||
          promise_result.set_value(cb_f.get()->result);
 | 
					          promise_result.set_value(cb_f.get()->result);
 | 
				
			||||||
          if (callback != nullptr) {
 | 
					          if (callback != nullptr) {
 | 
				
			||||||
            callback(future_result);
 | 
					            callback(future_result);
 | 
				
			||||||
| 
						 | 
					@ -192,24 +192,24 @@ public:
 | 
				
			||||||
    return future_result;
 | 
					    return future_result;
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::shared_future<rcl_interfaces::ListParametersResult>
 | 
					  std::shared_future<rcl_interfaces::msg::ListParametersResult>
 | 
				
			||||||
  list_parameters(
 | 
					  list_parameters(
 | 
				
			||||||
    std::vector<std::string> parameter_prefixes,
 | 
					    std::vector<std::string> parameter_prefixes,
 | 
				
			||||||
    uint64_t depth,
 | 
					    uint64_t depth,
 | 
				
			||||||
    std::function<void(
 | 
					    std::function<void(
 | 
				
			||||||
      std::shared_future<rcl_interfaces::ListParametersResult>)> callback = nullptr)
 | 
					      std::shared_future<rcl_interfaces::msg::ListParametersResult>)> callback = nullptr)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    std::promise<rcl_interfaces::ListParametersResult> promise_result;
 | 
					    std::promise<rcl_interfaces::msg::ListParametersResult> promise_result;
 | 
				
			||||||
    auto future_result = promise_result.get_future().share();
 | 
					    auto future_result = promise_result.get_future().share();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    auto request = std::make_shared<rcl_interfaces::ListParameters::Request>();
 | 
					    auto request = std::make_shared<rcl_interfaces::srv::ListParameters::Request>();
 | 
				
			||||||
    request->parameter_prefixes = parameter_prefixes;
 | 
					    request->parameter_prefixes = parameter_prefixes;
 | 
				
			||||||
    request->depth = depth;
 | 
					    request->depth = depth;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    list_parameters_client_->async_send_request(
 | 
					    list_parameters_client_->async_send_request(
 | 
				
			||||||
      request,
 | 
					      request,
 | 
				
			||||||
      [&promise_result, &future_result, &callback](
 | 
					      [&promise_result, &future_result, &callback](
 | 
				
			||||||
        rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedFuture cb_f) {
 | 
					        rclcpp::client::Client<rcl_interfaces::srv::ListParameters>::SharedFuture cb_f) {
 | 
				
			||||||
          promise_result.set_value(cb_f.get()->result);
 | 
					          promise_result.set_value(cb_f.get()->result);
 | 
				
			||||||
          if (callback != nullptr) {
 | 
					          if (callback != nullptr) {
 | 
				
			||||||
            callback(future_result);
 | 
					            callback(future_result);
 | 
				
			||||||
| 
						 | 
					@ -222,13 +222,15 @@ public:
 | 
				
			||||||
 | 
					
 | 
				
			||||||
private:
 | 
					private:
 | 
				
			||||||
  const rclcpp::node::Node::SharedPtr node_;
 | 
					  const rclcpp::node::Node::SharedPtr node_;
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::GetParameters>::SharedPtr get_parameters_client_;
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::GetParameters>::SharedPtr get_parameters_client_;
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::GetParameterTypes>::SharedPtr get_parameter_types_client_;
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::GetParameterTypes>::SharedPtr
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::SetParameters>::SharedPtr set_parameters_client_;
 | 
					    get_parameter_types_client_;
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::SetParametersAtomically>::SharedPtr
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::SetParameters>::SharedPtr set_parameters_client_;
 | 
				
			||||||
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::SetParametersAtomically>::SharedPtr
 | 
				
			||||||
    set_parameters_atomically_client_;
 | 
					    set_parameters_atomically_client_;
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::ListParameters>::SharedPtr list_parameters_client_;
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::ListParameters>::SharedPtr list_parameters_client_;
 | 
				
			||||||
  rclcpp::client::Client<rcl_interfaces::DescribeParameters>::SharedPtr describe_parameters_client_;
 | 
					  rclcpp::client::Client<rcl_interfaces::srv::DescribeParameters>::SharedPtr
 | 
				
			||||||
 | 
					    describe_parameters_client_;
 | 
				
			||||||
  std::string remote_node_name_;
 | 
					  std::string remote_node_name_;
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
| 
						 | 
					@ -267,21 +269,21 @@ public:
 | 
				
			||||||
    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
					    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  std::vector<rcl_interfaces::SetParametersResult>
 | 
					  std::vector<rcl_interfaces::msg::SetParametersResult>
 | 
				
			||||||
  set_parameters(std::vector<rclcpp::parameter::ParameterVariant> parameters)
 | 
					  set_parameters(std::vector<rclcpp::parameter::ParameterVariant> parameters)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    auto f = async_parameters_client_->set_parameters(parameters);
 | 
					    auto f = async_parameters_client_->set_parameters(parameters);
 | 
				
			||||||
    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
					    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  rcl_interfaces::SetParametersResult
 | 
					  rcl_interfaces::msg::SetParametersResult
 | 
				
			||||||
  set_parameters_atomically(std::vector<rclcpp::parameter::ParameterVariant> parameters)
 | 
					  set_parameters_atomically(std::vector<rclcpp::parameter::ParameterVariant> parameters)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    auto f = async_parameters_client_->set_parameters_atomically(parameters);
 | 
					    auto f = async_parameters_client_->set_parameters_atomically(parameters);
 | 
				
			||||||
    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
					    return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
 | 
				
			||||||
  }
 | 
					  }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  rcl_interfaces::ListParametersResult
 | 
					  rcl_interfaces::msg::ListParametersResult
 | 
				
			||||||
  list_parameters(
 | 
					  list_parameters(
 | 
				
			||||||
    std::vector<std::string> parameter_prefixes,
 | 
					    std::vector<std::string> parameter_prefixes,
 | 
				
			||||||
    uint64_t depth)
 | 
					    uint64_t depth)
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
| 
						 | 
					@ -24,15 +24,12 @@
 | 
				
			||||||
#include <rclcpp/node.hpp>
 | 
					#include <rclcpp/node.hpp>
 | 
				
			||||||
#include <rclcpp/parameter.hpp>
 | 
					#include <rclcpp/parameter.hpp>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <rcl_interfaces/GetParameters.h>
 | 
					#include <rcl_interfaces/srv/describe_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/GetParameterTypes.h>
 | 
					#include <rcl_interfaces/srv/get_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/Parameter.h>
 | 
					#include <rcl_interfaces/srv/get_parameter_types.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ParameterDescriptor.h>
 | 
					#include <rcl_interfaces/srv/list_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/ParameterType.h>
 | 
					#include <rcl_interfaces/srv/set_parameters.hpp>
 | 
				
			||||||
#include <rcl_interfaces/SetParameters.h>
 | 
					#include <rcl_interfaces/srv/set_parameters_atomically.hpp>
 | 
				
			||||||
#include <rcl_interfaces/SetParametersAtomically.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/ListParameters.h>
 | 
					 | 
				
			||||||
#include <rcl_interfaces/DescribeParameters.h>
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
namespace rclcpp
 | 
					namespace rclcpp
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
| 
						 | 
					@ -49,11 +46,11 @@ public:
 | 
				
			||||||
  ParameterService(const rclcpp::node::Node::SharedPtr & node)
 | 
					  ParameterService(const rclcpp::node::Node::SharedPtr & node)
 | 
				
			||||||
  : node_(node)
 | 
					  : node_(node)
 | 
				
			||||||
  {
 | 
					  {
 | 
				
			||||||
    get_parameters_service_ = node_->create_service<rcl_interfaces::GetParameters>(
 | 
					    get_parameters_service_ = node_->create_service<rcl_interfaces::srv::GetParameters>(
 | 
				
			||||||
      node_->get_name() + "__get_parameters", [&node](
 | 
					      node_->get_name() + "__get_parameters", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::GetParameters::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::GetParameters::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          auto values = node->get_parameters(request->names);
 | 
					          auto values = node->get_parameters(request->names);
 | 
				
			||||||
          std::transform(values.cbegin(), values.cend(), std::back_inserter(response->values),
 | 
					          std::transform(values.cbegin(), values.cend(), std::back_inserter(response->values),
 | 
				
			||||||
| 
						 | 
					@ -64,11 +61,11 @@ public:
 | 
				
			||||||
        }
 | 
					        }
 | 
				
			||||||
      );
 | 
					      );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    get_parameter_types_service_ = node_->create_service<rcl_interfaces::GetParameterTypes>(
 | 
					    get_parameter_types_service_ = node_->create_service<rcl_interfaces::srv::GetParameterTypes>(
 | 
				
			||||||
      node_->get_name() + "__get_parameter_types", [&node](
 | 
					      node_->get_name() + "__get_parameter_types", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::GetParameterTypes::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::GetParameterTypes::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          auto types = node->get_parameter_types(request->parameter_names);
 | 
					          auto types = node->get_parameter_types(request->parameter_names);
 | 
				
			||||||
          std::transform(types.cbegin(), types.cend(),
 | 
					          std::transform(types.cbegin(), types.cend(),
 | 
				
			||||||
| 
						 | 
					@ -78,16 +75,16 @@ public:
 | 
				
			||||||
        }
 | 
					        }
 | 
				
			||||||
      );
 | 
					      );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    set_parameters_service_ = node_->create_service<rcl_interfaces::SetParameters>(
 | 
					    set_parameters_service_ = node_->create_service<rcl_interfaces::srv::SetParameters>(
 | 
				
			||||||
      node_->get_name() + "__set_parameters", [&node](
 | 
					      node_->get_name() + "__set_parameters", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::SetParameters::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::SetParameters::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          std::vector<rclcpp::parameter::ParameterVariant> pvariants;
 | 
					          std::vector<rclcpp::parameter::ParameterVariant> pvariants;
 | 
				
			||||||
          std::transform(request->parameters.cbegin(), request->parameters.cend(),
 | 
					          std::transform(request->parameters.cbegin(), request->parameters.cend(),
 | 
				
			||||||
          std::back_inserter(pvariants),
 | 
					          std::back_inserter(pvariants),
 | 
				
			||||||
          [](const rcl_interfaces::Parameter & p) {
 | 
					          [](const rcl_interfaces::msg::Parameter & p) {
 | 
				
			||||||
            return rclcpp::parameter::ParameterVariant::
 | 
					            return rclcpp::parameter::ParameterVariant::
 | 
				
			||||||
            from_parameter(p);
 | 
					            from_parameter(p);
 | 
				
			||||||
          });
 | 
					          });
 | 
				
			||||||
| 
						 | 
					@ -97,16 +94,16 @@ public:
 | 
				
			||||||
      );
 | 
					      );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    set_parameters_atomically_service_ =
 | 
					    set_parameters_atomically_service_ =
 | 
				
			||||||
      node_->create_service<rcl_interfaces::SetParametersAtomically>(
 | 
					      node_->create_service<rcl_interfaces::srv::SetParametersAtomically>(
 | 
				
			||||||
      node_->get_name() + "__set_parameters_atomically", [&node](
 | 
					      node_->get_name() + "__set_parameters_atomically", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::SetParametersAtomically::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::SetParametersAtomically::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          std::vector<rclcpp::parameter::ParameterVariant> pvariants;
 | 
					          std::vector<rclcpp::parameter::ParameterVariant> pvariants;
 | 
				
			||||||
          std::transform(request->parameters.cbegin(), request->parameters.cend(),
 | 
					          std::transform(request->parameters.cbegin(), request->parameters.cend(),
 | 
				
			||||||
          std::back_inserter(pvariants),
 | 
					          std::back_inserter(pvariants),
 | 
				
			||||||
          [](const rcl_interfaces::Parameter & p) {
 | 
					          [](const rcl_interfaces::msg::Parameter & p) {
 | 
				
			||||||
            return rclcpp::parameter::ParameterVariant::
 | 
					            return rclcpp::parameter::ParameterVariant::
 | 
				
			||||||
            from_parameter(p);
 | 
					            from_parameter(p);
 | 
				
			||||||
          });
 | 
					          });
 | 
				
			||||||
| 
						 | 
					@ -115,22 +112,22 @@ public:
 | 
				
			||||||
        }
 | 
					        }
 | 
				
			||||||
      );
 | 
					      );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    describe_parameters_service_ = node_->create_service<rcl_interfaces::DescribeParameters>(
 | 
					    describe_parameters_service_ = node_->create_service<rcl_interfaces::srv::DescribeParameters>(
 | 
				
			||||||
      node_->get_name() + "__describe_parameters", [&node](
 | 
					      node_->get_name() + "__describe_parameters", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::DescribeParameters::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::DescribeParameters::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          auto descriptors = node->describe_parameters(request->names);
 | 
					          auto descriptors = node->describe_parameters(request->names);
 | 
				
			||||||
          response->descriptors = descriptors;
 | 
					          response->descriptors = descriptors;
 | 
				
			||||||
        }
 | 
					        }
 | 
				
			||||||
      );
 | 
					      );
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    list_parameters_service_ = node_->create_service<rcl_interfaces::ListParameters>(
 | 
					    list_parameters_service_ = node_->create_service<rcl_interfaces::srv::ListParameters>(
 | 
				
			||||||
      node_->get_name() + "__describe_parameters", [&node](
 | 
					      node_->get_name() + "__describe_parameters", [&node](
 | 
				
			||||||
        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
					        const std::shared_ptr<rmw_request_id_t> request_header,
 | 
				
			||||||
        const std::shared_ptr<rcl_interfaces::ListParameters::Request> request,
 | 
					        const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
 | 
				
			||||||
        std::shared_ptr<rcl_interfaces::ListParameters::Response> response)
 | 
					        std::shared_ptr<rcl_interfaces::srv::ListParameters::Response> response)
 | 
				
			||||||
        {
 | 
					        {
 | 
				
			||||||
          auto result = node->list_parameters(request->parameter_prefixes, request->depth);
 | 
					          auto result = node->list_parameters(request->parameter_prefixes, request->depth);
 | 
				
			||||||
          response->result = result;
 | 
					          response->result = result;
 | 
				
			||||||
| 
						 | 
					@ -142,15 +139,15 @@ public:
 | 
				
			||||||
 | 
					
 | 
				
			||||||
private:
 | 
					private:
 | 
				
			||||||
  const rclcpp::node::Node::SharedPtr node_;
 | 
					  const rclcpp::node::Node::SharedPtr node_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::GetParameters>::SharedPtr get_parameters_service_;
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::GetParameters>::SharedPtr get_parameters_service_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::GetParameterTypes>::SharedPtr
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::GetParameterTypes>::SharedPtr
 | 
				
			||||||
    get_parameter_types_service_;
 | 
					    get_parameter_types_service_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::SetParameters>::SharedPtr set_parameters_service_;
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::SetParameters>::SharedPtr set_parameters_service_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::SetParametersAtomically>::SharedPtr
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::SetParametersAtomically>::SharedPtr
 | 
				
			||||||
    set_parameters_atomically_service_;
 | 
					    set_parameters_atomically_service_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::DescribeParameters>::SharedPtr
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::DescribeParameters>::SharedPtr
 | 
				
			||||||
    describe_parameters_service_;
 | 
					    describe_parameters_service_;
 | 
				
			||||||
  rclcpp::service::Service<rcl_interfaces::ListParameters>::SharedPtr list_parameters_service_;
 | 
					  rclcpp::service::Service<rcl_interfaces::srv::ListParameters>::SharedPtr list_parameters_service_;
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
} /* namespace parameter_service */
 | 
					} /* namespace parameter_service */
 | 
				
			||||||
| 
						 | 
					
 | 
				
			||||||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue