ROS 2 rclcpp + rcl - humble  humble
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 rmw_qos_profile_t & 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());
51  }
52  },
53  qos_profile, nullptr);
54 
55  get_parameter_types_service_ = create_service<rcl_interfaces::srv::GetParameterTypes>(
56  node_base, node_services,
57  node_name + "/" + parameter_service_names::get_parameter_types,
58  [node_params](
59  const std::shared_ptr<rmw_request_id_t>,
60  const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request,
61  std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response)
62  {
63  try {
64  auto types = node_params->get_parameter_types(request->names);
65  std::transform(
66  types.cbegin(), types.cend(),
67  std::back_inserter(response->types), [](const uint8_t & type) {
68  return static_cast<rclcpp::ParameterType>(type);
69  });
71  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what());
72  }
73  },
74  qos_profile, nullptr);
75 
76  set_parameters_service_ = create_service<rcl_interfaces::srv::SetParameters>(
77  node_base, node_services,
78  node_name + "/" + parameter_service_names::set_parameters,
79  [node_params](
80  const std::shared_ptr<rmw_request_id_t>,
81  const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
82  std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
83  {
84  // Set parameters one-by-one, since there's no way to return a partial result if
85  // set_parameters() fails.
86  auto result = rcl_interfaces::msg::SetParametersResult();
87  for (auto & p : request->parameters) {
88  try {
89  result = node_params->set_parameters_atomically(
92  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to set parameter: %s", ex.what());
93  result.successful = false;
94  result.reason = ex.what();
95  }
96  response->results.push_back(result);
97  }
98  },
99  qos_profile, nullptr);
100 
101  set_parameters_atomically_service_ = create_service<rcl_interfaces::srv::SetParametersAtomically>(
102  node_base, node_services,
103  node_name + "/" + parameter_service_names::set_parameters_atomically,
104  [node_params](
105  const std::shared_ptr<rmw_request_id_t>,
106  const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
107  std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
108  {
109  std::vector<rclcpp::Parameter> pvariants;
110  std::transform(
111  request->parameters.cbegin(), request->parameters.cend(),
112  std::back_inserter(pvariants),
113  [](const rcl_interfaces::msg::Parameter & p) {
114  return rclcpp::Parameter::from_parameter_msg(p);
115  });
116  try {
117  auto result = node_params->set_parameters_atomically(pvariants);
118  response->result = result;
120  RCLCPP_DEBUG(
121  rclcpp::get_logger("rclcpp"), "Failed to set parameters atomically: %s", ex.what());
122  response->result.successful = false;
123  response->result.reason = "One or more parameters were not declared before setting";
124  }
125  },
126  qos_profile, nullptr);
127 
128  describe_parameters_service_ = create_service<rcl_interfaces::srv::DescribeParameters>(
129  node_base, node_services,
130  node_name + "/" + parameter_service_names::describe_parameters,
131  [node_params](
132  const std::shared_ptr<rmw_request_id_t>,
133  const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request,
134  std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response)
135  {
136  try {
137  auto descriptors = node_params->describe_parameters(request->names);
138  response->descriptors = descriptors;
140  RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to describe parameters: %s", ex.what());
141  }
142  },
143  qos_profile, nullptr);
144 
145  list_parameters_service_ = create_service<rcl_interfaces::srv::ListParameters>(
146  node_base, node_services,
147  node_name + "/" + parameter_service_names::list_parameters,
148  [node_params](
149  const std::shared_ptr<rmw_request_id_t>,
150  const std::shared_ptr<rcl_interfaces::srv::ListParameters::Request> request,
151  std::shared_ptr<rcl_interfaces::srv::ListParameters::Response> response)
152  {
153  auto result = node_params->list_parameters(request->prefixes, request->depth);
154  response->result = result;
155  },
156  qos_profile, nullptr);
157 }
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
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Definition: exceptions.hpp:285
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:27