ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
parameter_service.cpp
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "rclcpp/parameter_service.hpp"
16 
17 #include <algorithm>
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "rclcpp/logging.hpp"
23 
24 #include "./parameter_service_names.hpp"
25 
27 
28 ParameterService::ParameterService(
29  const std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base,
30  const std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface> node_services,
32  const rclcpp::QoS & qos_profile)
33 {
34  const std::string node_name = node_base->get_name();
35 
36  get_parameters_service_ = create_service<rcl_interfaces::srv::GetParameters>(
37  node_base, node_services,
38  node_name + "/" + parameter_service_names::get_parameters,
39  [node_params](
40  const std::shared_ptr<rmw_request_id_t>,
41  const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request,
42  std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response)
43  {
44  try {
45  auto parameters = node_params->get_parameters(request->names);
46  for (const auto & param : parameters) {
47  response->values.push_back(param.get_value_message());
48  }
50  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what());
52  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what());
53  }
54  },
55  qos_profile, nullptr);
56 
57  get_parameter_types_service_ = create_service<rcl_interfaces::srv::GetParameterTypes>(
58  node_base, node_services,
59  node_name + "/" + parameter_service_names::get_parameter_types,
60  [node_params](
61  const std::shared_ptr<rmw_request_id_t>,
62  const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
63  std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response)
64  {
65  try {
66  auto types = node_params->get_parameter_types(request->names);
67  std::transform(
68  types.cbegin(), types.cend(),
69  std::back_inserter(response->types), [](const uint8_t & type) {
70  return static_cast<rclcpp::ParameterType>(type);
71  });
73  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what());
74  }
75  },
76  qos_profile, nullptr);
77 
78  set_parameters_service_ = create_service<rcl_interfaces::srv::SetParameters>(
79  node_base, node_services,
80  node_name + "/" + parameter_service_names::set_parameters,
81  [node_params](
82  const std::shared_ptr<rmw_request_id_t>,
83  const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
84  std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
85  {
86  // Set parameters one-by-one, since there's no way to return a partial result if
87  // set_parameters() fails.
88  auto result = rcl_interfaces::msg::SetParametersResult();
89  for (auto & p : request->parameters) {
90  try {
91  result = node_params->set_parameters_atomically(
94  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to set parameter: %s", ex.what());
95  result.successful = false;
96  result.reason = ex.what();
97  }
98  response->results.push_back(result);
99  }
100  },
101  qos_profile, nullptr);
102 
103  set_parameters_atomically_service_ = create_service<rcl_interfaces::srv::SetParametersAtomically>(
104  node_base, node_services,
105  node_name + "/" + parameter_service_names::set_parameters_atomically,
106  [node_params](
107  const std::shared_ptr<rmw_request_id_t>,
108  const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
109  std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
110  {
111  std::vector<rclcpp::Parameter> pvariants;
112  std::transform(
113  request->parameters.cbegin(), request->parameters.cend(),
114  std::back_inserter(pvariants),
115  [](const rcl_interfaces::msg::Parameter & p) {
116  return rclcpp::Parameter::from_parameter_msg(p);
117  });
118  try {
119  auto result = node_params->set_parameters_atomically(pvariants);
120  response->result = result;
122  RCLCPP_DEBUG(
123  rclcpp::get_logger("rclcpp"), "Failed to set parameters atomically: %s", ex.what());
124  response->result.successful = false;
125  response->result.reason = "One or more parameters were not declared before setting";
126  }
127  },
128  qos_profile, nullptr);
129 
130  describe_parameters_service_ = create_service<rcl_interfaces::srv::DescribeParameters>(
131  node_base, node_services,
132  node_name + "/" + parameter_service_names::describe_parameters,
133  [node_params](
134  const std::shared_ptr<rmw_request_id_t>,
135  const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
136  std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response)
137  {
138  try {
139  auto descriptors = node_params->describe_parameters(request->names);
140  response->descriptors = descriptors;
142  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to describe parameters: %s", ex.what());
143  }
144  },
145  qos_profile, nullptr);
146 
147  list_parameters_service_ = create_service<rcl_interfaces::srv::ListParameters>(
148  node_base, node_services,
149  node_name + "/" + parameter_service_names::list_parameters,
150  [node_params](
151  const std::shared_ptr<rmw_request_id_t>,
152  const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
153  std::shared_ptr<rcl_interfaces::srv::ListParameters::Response> response)
154  {
155  auto result = node_params->list_parameters(request->prefixes, request->depth);
156  response->result = result;
157  },
158  qos_profile, nullptr);
159 }
static RCLCPP_PUBLIC Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter &parameter)
Convert a parameter message in a Parameter class object.
Definition: parameter.cpp:145
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Definition: exceptions.hpp:310
Thrown when an uninitialized parameter is accessed.
Definition: exceptions.hpp:331
Pure virtual interface class for the NodeParameters part of the Node API.
virtual RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const =0
Get descriptions of parameters given their names.
virtual RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)=0
Set one or more parameters, all at once.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:34