15 #include "rclcpp/parameter_service.hpp"
22 #include "rclcpp/logging.hpp"
24 #include "./parameter_service_names.hpp"
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)
34 const std::string node_name = node_base->get_name();
36 get_parameters_service_ = create_service<rcl_interfaces::srv::GetParameters>(
37 node_base, node_services,
38 node_name +
"/" + parameter_service_names::get_parameters,
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)
46 for (
const auto & param : parameters) {
47 response->values.push_back(param.get_value_message());
53 qos_profile,
nullptr);
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,
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)
64 auto types = node_params->get_parameter_types(request->names);
66 types.cbegin(), types.cend(),
67 std::back_inserter(response->types), [](
const uint8_t & type) {
68 return static_cast<rclcpp::ParameterType>(type);
71 RCLCPP_DEBUG(
rclcpp::get_logger(
"rclcpp"),
"Failed to get parameter types: %s", ex.what());
74 qos_profile,
nullptr);
76 set_parameters_service_ = create_service<rcl_interfaces::srv::SetParameters>(
77 node_base, node_services,
78 node_name +
"/" + parameter_service_names::set_parameters,
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)
86 auto result = rcl_interfaces::msg::SetParametersResult();
87 for (
auto & p : request->parameters) {
93 result.successful =
false;
94 result.reason = ex.what();
96 response->results.push_back(result);
99 qos_profile,
nullptr);
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,
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)
109 std::vector<rclcpp::Parameter> pvariants;
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);
118 response->result = result;
122 response->result.successful =
false;
123 response->result.reason =
"One or more parameters were not declared before setting";
126 qos_profile,
nullptr);
128 describe_parameters_service_ = create_service<rcl_interfaces::srv::DescribeParameters>(
129 node_base, node_services,
130 node_name +
"/" + parameter_service_names::describe_parameters,
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)
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());
143 qos_profile,
nullptr);
145 list_parameters_service_ = create_service<rcl_interfaces::srv::ListParameters>(
146 node_base, node_services,
147 node_name +
"/" + parameter_service_names::list_parameters,
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)
153 auto result = node_params->list_parameters(request->prefixes, request->depth);
154 response->result = result;
156 qos_profile,
nullptr);
static RCLCPP_PUBLIC Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter ¶meter)
Convert a parameter message in a Parameter class object.
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
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 > ¶meters)=0
Set one or more parameters, all at once.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.