From def40f4dc7b98f897fa4e196aea1ea3a379c4662 Mon Sep 17 00:00:00 2001 From: domire8 Date: Mon, 9 Dec 2024 14:50:47 +0000 Subject: [PATCH] deploy: d8343e18dd205037c7644bb47335440fe3ac9799 --- ...base_controller_interface_8cpp_source.html | 1298 +++++++--------- ...base_controller_interface_8hpp_source.html | 1334 ++++++++--------- .../_component_interface_8cpp_source.html | 2 +- .../_controller_interface_8cpp_source.html | 14 +- .../_controller_interface_8hpp_source.html | 4 +- ...obot_controller_interface_8cpp_source.html | 4 +- ...obot_controller_interface_8hpp_source.html | 2 +- ...1_1_base_controller_interface-members.html | 26 +- ...rollers_1_1_base_controller_interface.html | 509 +------ ...lers_1_1_controller_interface-members.html | 40 +- ..._controllers_1_1_controller_interface.html | 30 - ..._1_robot_controller_interface-members.html | 52 +- ...ollers_1_1_robot_controller_interface.html | 30 - versions/main/functions.html | 19 +- versions/main/functions_func.html | 19 +- versions/main/search/all_0.js | 10 +- versions/main/search/all_8.js | 3 +- versions/main/search/all_9.js | 2 +- versions/main/search/all_f.js | 12 +- versions/main/search/functions_0.js | 14 +- versions/main/search/functions_7.js | 3 +- versions/main/search/functions_8.js | 2 +- versions/main/search/functions_d.js | 14 +- ...ulo__controllers_1_1_controller_input.html | 8 +- ...llers_1_1_controller_service_response.html | 6 +- 25 files changed, 1357 insertions(+), 2100 deletions(-) diff --git a/versions/main/_base_controller_interface_8cpp_source.html b/versions/main/_base_controller_interface_8cpp_source.html index acbd39d0b..0aeeeb7d3 100644 --- a/versions/main/_base_controller_interface_8cpp_source.html +++ b/versions/main/_base_controller_interface_8cpp_source.html @@ -85,766 +85,626 @@
2
3#include <chrono>
4
-
5#include <console_bridge/console.h>
+
5#include <lifecycle_msgs/msg/state.hpp>
6
-
7#include <lifecycle_msgs/msg/state.hpp>
+
7#include <modulo_core/translators/message_readers.hpp>
8
-
9#include <modulo_core/exceptions.hpp>
-
10#include <modulo_core/translators/message_readers.hpp>
-
11#include <stdexcept>
-
12
+
9template<class... Ts>
+
10struct overloaded : Ts... {
+
11 using Ts::operator()...;
+
12};
13template<class... Ts>
-
14struct overloaded : Ts... {
-
15 using Ts::operator()...;
-
16};
-
17template<class... Ts>
-
18overloaded(Ts...) -> overloaded<Ts...>;
+
14overloaded(Ts...) -> overloaded<Ts...>;
+
15
+
16using namespace modulo_core;
+
17using namespace state_representation;
+
18using namespace std::chrono_literals;
19
-
20using namespace modulo_core;
-
21using namespace state_representation;
-
22using namespace std::chrono_literals;
-
23
-
24namespace modulo_controllers {
-
25
-
- -
27 : controller_interface::ControllerInterface(), input_validity_period_(std::numeric_limits<double>::quiet_NaN()) {}
+
20namespace modulo_controllers {
+
21
+
+ +
23 : controller_interface::ControllerInterface(), input_validity_period_(std::numeric_limits<double>::quiet_NaN()) {}
+
+
24
+
+
25rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn BaseControllerInterface::on_init() {
+
26 // registering set_parameter callbacks is only possible on_init since the lifecycle node is not yet initialized
+
27 // on construction. This means we might not be able to validate parameter overrides - if they are provided.
+
28 pre_set_parameter_cb_handle_ = get_node()->add_pre_set_parameters_callback(
+
29 [this](std::vector<rclcpp::Parameter>& parameters) { return this->pre_set_parameters_callback(parameters); });
+
30 on_set_parameter_cb_handle_ = get_node()->add_on_set_parameters_callback(
+
31 [this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
+
32 return this->on_set_parameters_callback(parameters);
+
33 });
+
34 add_parameter<double>("predicate_publishing_rate", 10.0, "The rate at which to publish controller predicates");
+
35 return CallbackReturn::SUCCESS;
+
36}
+
+
37
+
38rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
+
+
39BaseControllerInterface::on_configure(const rclcpp_lifecycle::State&) {
+
40 add_inputs();
+
41 add_outputs();
+
42
+
43 if (predicates_.size()) {
+
44 predicate_publisher_ =
+
45 get_node()->create_publisher<modulo_interfaces::msg::PredicateCollection>("/predicates", qos_);
+
46 predicate_message_.node = get_node()->get_fully_qualified_name();
+
47 predicate_message_.type = modulo_interfaces::msg::PredicateCollection::CONTROLLER;
+
48
+
49 predicate_timer_ = get_node()->create_wall_timer(
+
50 std::chrono::nanoseconds(static_cast<int64_t>(1e9 / get_parameter_value<double>("predicate_publishing_rate"))),
+
51 [this]() { this->publish_predicates(); });
+
52 }
+
53
+
54 RCLCPP_DEBUG(get_node()->get_logger(), "Configuration of BaseControllerInterface successful");
+
55 return CallbackReturn::SUCCESS;
+
56}
-
28
-
-
29rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn BaseControllerInterface::on_init() {
-
30 // registering set_parameter callbacks is only possible on_init since the lifecycle node is not yet initialized
-
31 // on construction. This means we might not be able to validate parameter overrides - if they are provided.
-
32 pre_set_parameter_cb_handle_ = get_node()->add_pre_set_parameters_callback(
-
33 [this](std::vector<rclcpp::Parameter>& parameters) { return this->pre_set_parameters_callback(parameters); });
-
34 on_set_parameter_cb_handle_ = get_node()->add_on_set_parameters_callback(
-
35 [this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
-
36 return this->on_set_parameters_callback(parameters);
-
37 });
-
38 add_parameter<double>("predicate_publishing_rate", 10.0, "The rate at which to publish controller predicates");
-
39 return CallbackReturn::SUCCESS;
-
40}
-
-
41
-
42rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
-
-
43BaseControllerInterface::on_configure(const rclcpp_lifecycle::State&) {
-
44 add_inputs();
-
45 add_outputs();
-
46
-
47 if (predicates_.size()) {
-
48 predicate_publisher_ =
-
49 get_node()->create_publisher<modulo_interfaces::msg::PredicateCollection>("/predicates", qos_);
-
50 predicate_message_.node = get_node()->get_fully_qualified_name();
-
51 predicate_message_.type = modulo_interfaces::msg::PredicateCollection::CONTROLLER;
-
52
-
53 predicate_timer_ = get_node()->create_wall_timer(
-
54 std::chrono::nanoseconds(static_cast<int64_t>(1e9 / get_parameter_value<double>("predicate_publishing_rate"))),
-
55 [this]() { this->publish_predicates(); });
-
56 }
57
-
58 RCLCPP_DEBUG(get_node()->get_logger(), "Configuration of BaseControllerInterface successful");
-
59 return CallbackReturn::SUCCESS;
-
60}
-
-
61
- -
63 const std::shared_ptr<ParameterInterface>& parameter, const std::string& description, bool read_only) {
-
64 rclcpp::Parameter ros_param;
-
65 try {
- - -
68 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
-
69 }
-
70 if (!get_node()->has_parameter(parameter->get_name())) {
-
71 RCLCPP_DEBUG(get_node()->get_logger(), "Adding parameter '%s'.", parameter->get_name().c_str());
-
72 parameter_map_.set_parameter(parameter);
-
73 read_only_parameters_.insert_or_assign(parameter->get_name(), false);
-
74 try {
-
75 rcl_interfaces::msg::ParameterDescriptor descriptor;
-
76 descriptor.description = description;
-
77 descriptor.read_only = read_only;
-
78 // since the pre_set_parameters_callback is not called on parameter declaration, this has to be true
-
79 set_parameters_result_.successful = true;
-
80 set_parameters_result_.reason = "";
-
81 if (parameter->is_empty()) {
-
82 descriptor.dynamic_typing = true;
-
83 descriptor.type = translators::get_ros_parameter_type(parameter->get_parameter_type());
-
84 get_node()->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
-
85 } else {
-
86 get_node()->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
-
87 }
-
88 std::vector<rclcpp::Parameter> ros_parameters{get_node()->get_parameters({parameter->get_name()})};
-
89 pre_set_parameters_callback(ros_parameters);
-
90 auto result = on_set_parameters_callback(ros_parameters);
-
91 if (!result.successful) {
-
92 get_node()->undeclare_parameter(parameter->get_name());
- -
94 }
-
95 read_only_parameters_.at(parameter->get_name()) = read_only;
-
96 } catch (const std::exception& ex) {
-
97 parameter_map_.remove_parameter(parameter->get_name());
-
98 read_only_parameters_.erase(parameter->get_name());
-
99 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
-
100 }
-
101 } else {
-
102 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' already exists.", parameter->get_name().c_str());
-
103 }
-
104}
-
105
-
-
106std::shared_ptr<ParameterInterface> BaseControllerInterface::get_parameter(const std::string& name) const {
-
107 try {
-
108 return parameter_map_.get_parameter(name);
-
109 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
-
110 throw modulo_core::exceptions::ParameterException("Failed to get parameter '" + name + "': " + ex.what());
-
111 }
-
112}
-
-
113
-
114void BaseControllerInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
-
115 if (pre_set_parameter_callback_called_) {
-
116 pre_set_parameter_callback_called_ = false;
-
117 return;
-
118 }
-
119 rcl_interfaces::msg::SetParametersResult result;
-
120 result.successful = true;
-
121 for (auto& ros_parameter : parameters) {
-
122 try {
-
123 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
-
124 if (read_only_parameters_.at(ros_parameter.get_name())) {
-
125 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' is read only.", ros_parameter.get_name().c_str());
-
126 continue;
-
127 }
-
128
-
129 // convert the ROS parameter into a ParameterInterface without modifying the original
- -
131 if (!this->validate_parameter(new_parameter)) {
-
132 result.successful = false;
-
133 result.reason += "Validation of parameter '" + ros_parameter.get_name() + "' returned false!";
-
134 } else if (!new_parameter->is_empty()) {
-
135 // update the value of the parameter in the map
- - -
138 }
-
139 } catch (const std::exception& ex) {
-
140 result.successful = false;
-
141 result.reason += ex.what();
-
142 }
-
143 }
-
144 set_parameters_result_ = result;
-
145}
-
146
-
147rcl_interfaces::msg::SetParametersResult
-
148BaseControllerInterface::on_set_parameters_callback(const std::vector<rclcpp::Parameter>&) {
-
149 auto result = set_parameters_result_;
-
150 set_parameters_result_.successful = true;
-
151 set_parameters_result_.reason = "";
-
152 return result;
-
153}
-
154
-
155bool BaseControllerInterface::validate_parameter(const std::shared_ptr<ParameterInterface>& parameter) {
-
156 if (parameter->get_name() == "activation_timeout" || parameter->get_name() == "input_validity_period") {
-
157 auto value = parameter->get_parameter_value<double>();
-
158 if (value < 0.0 || value > std::numeric_limits<double>::max()) {
- -
160 get_node()->get_logger(), "Parameter value of parameter '%s' should be a positive finite number",
-
161 parameter->get_name().c_str());
-
162 return false;
-
163 }
-
164 }
- + +
59 const std::shared_ptr<ParameterInterface>& parameter, const std::string& description, bool read_only) {
+
60 rclcpp::Parameter ros_param;
+
61 try {
+ + +
64 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
+
65 }
+
66 if (!get_node()->has_parameter(parameter->get_name())) {
+
67 RCLCPP_DEBUG(get_node()->get_logger(), "Adding parameter '%s'.", parameter->get_name().c_str());
+
68 parameter_map_.set_parameter(parameter);
+
69 read_only_parameters_.insert_or_assign(parameter->get_name(), false);
+
70 try {
+
71 rcl_interfaces::msg::ParameterDescriptor descriptor;
+
72 descriptor.description = description;
+
73 descriptor.read_only = read_only;
+
74 // since the pre_set_parameters_callback is not called on parameter declaration, this has to be true
+
75 set_parameters_result_.successful = true;
+
76 set_parameters_result_.reason = "";
+
77 if (parameter->is_empty()) {
+
78 descriptor.dynamic_typing = true;
+
79 descriptor.type = translators::get_ros_parameter_type(parameter->get_parameter_type());
+
80 get_node()->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
+
81 } else {
+
82 get_node()->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
+
83 }
+
84 std::vector<rclcpp::Parameter> ros_parameters{get_node()->get_parameters({parameter->get_name()})};
+
85 pre_set_parameters_callback(ros_parameters);
+
86 auto result = on_set_parameters_callback(ros_parameters);
+
87 if (!result.successful) {
+
88 get_node()->undeclare_parameter(parameter->get_name());
+ +
90 }
+
91 read_only_parameters_.at(parameter->get_name()) = read_only;
+
92 } catch (const std::exception& ex) {
+
93 parameter_map_.remove_parameter(parameter->get_name());
+
94 read_only_parameters_.erase(parameter->get_name());
+
95 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
+
96 }
+
97 } else {
+
98 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' already exists.", parameter->get_name().c_str());
+
99 }
+
100}
+
101
+
+
102std::shared_ptr<ParameterInterface> BaseControllerInterface::get_parameter(const std::string& name) const {
+
103 try {
+
104 return parameter_map_.get_parameter(name);
+
105 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
+
106 throw modulo_core::exceptions::ParameterException("Failed to get parameter '" + name + "': " + ex.what());
+
107 }
+
108}
+
+
109
+
110void BaseControllerInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
+
111 if (pre_set_parameter_callback_called_) {
+
112 pre_set_parameter_callback_called_ = false;
+
113 return;
+
114 }
+
115 rcl_interfaces::msg::SetParametersResult result;
+
116 result.successful = true;
+
117 for (auto& ros_parameter : parameters) {
+
118 try {
+
119 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
+
120 if (read_only_parameters_.at(ros_parameter.get_name())) {
+
121 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' is read only.", ros_parameter.get_name().c_str());
+
122 continue;
+
123 }
+
124
+
125 // convert the ROS parameter into a ParameterInterface without modifying the original
+ +
127 if (!this->validate_parameter(new_parameter)) {
+
128 result.successful = false;
+
129 result.reason += "Validation of parameter '" + ros_parameter.get_name() + "' returned false!";
+
130 } else if (!new_parameter->is_empty()) {
+
131 // update the value of the parameter in the map
+ + +
134 }
+
135 } catch (const std::exception& ex) {
+
136 result.successful = false;
+
137 result.reason += ex.what();
+
138 }
+
139 }
+
140 set_parameters_result_ = result;
+
141}
+
142
+
143rcl_interfaces::msg::SetParametersResult
+
144BaseControllerInterface::on_set_parameters_callback(const std::vector<rclcpp::Parameter>&) {
+
145 auto result = set_parameters_result_;
+
146 set_parameters_result_.successful = true;
+
147 set_parameters_result_.reason = "";
+
148 return result;
+
149}
+
150
+
151bool BaseControllerInterface::validate_parameter(const std::shared_ptr<ParameterInterface>& parameter) {
+
152 if (parameter->get_name() == "activation_timeout" || parameter->get_name() == "input_validity_period") {
+
153 auto value = parameter->get_parameter_value<double>();
+
154 if (value < 0.0 || value > std::numeric_limits<double>::max()) {
+ +
156 get_node()->get_logger(), "Parameter value of parameter '%s' should be a positive finite number",
+
157 parameter->get_name().c_str());
+
158 return false;
+
159 }
+
160 }
+ +
162}
+
163
+
+
164bool BaseControllerInterface::on_validate_parameter_callback(const std::shared_ptr<ParameterInterface>&) {
+
165 return true;
166}
+
167
-
168bool BaseControllerInterface::on_validate_parameter_callback(const std::shared_ptr<ParameterInterface>&) {
-
169 return true;
+
168void BaseControllerInterface::add_predicate(const std::string& predicate_name, bool predicate_value) {
+
170}
171
-
172void BaseControllerInterface::add_predicate(const std::string& predicate_name, bool predicate_value) {
- -
174}
-
-
175
-
- -
177 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
-
178 if (predicate_name.empty()) {
-
179 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add predicate: Provide a non empty string as a name.");
-
180 return;
-
181 }
-
182 if (predicates_.find(predicate_name) != predicates_.end()) {
- -
184 get_node()->get_logger(), "Predicate with name '%s' already exists, overwriting.", predicate_name.c_str());
-
185 } else {
-
186 RCLCPP_DEBUG(get_node()->get_logger(), "Adding predicate '%s'.", predicate_name.c_str());
-
187 }
-
188 try {
-
189 this->predicates_.insert_or_assign(predicate_name, Predicate(predicate_function));
-
190 } catch (const std::exception& ex) {
- -
192 get_node()->get_logger(), "Failed to evaluate callback of predicate '%s', returning false: %s",
-
193 predicate_name.c_str(), ex.what());
-
194 }
-
195}
-
-
196
-
-
197bool BaseControllerInterface::get_predicate(const std::string& predicate_name) const {
-
198 auto predicate_it = predicates_.find(predicate_name);
-
199 if (predicate_it == predicates_.end()) {
- -
201 get_node()->get_logger(), *get_node()->get_clock(), 1000,
-
202 "Failed to get predicate '%s': Predicate does not exists, returning false.", predicate_name.c_str());
-
203 return false;
-
204 }
-
205 try {
-
206 return predicate_it->second.get_value();
-
207 } catch (const std::exception& ex) {
- -
209 get_node()->get_logger(), *get_node()->get_clock(), 1000,
-
210 "Failed to evaluate callback of predicate '%s', returning false: %s", predicate_name.c_str(), ex.what());
-
211 }
-
212 return false;
+ +
173 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
+
174 if (predicate_name.empty()) {
+
175 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add predicate: Provide a non empty string as a name.");
+
176 return;
+
177 }
+
178 if (predicates_.find(predicate_name) != predicates_.end()) {
+ +
180 get_node()->get_logger(), "Predicate with name '%s' already exists, overwriting.", predicate_name.c_str());
+
181 } else {
+
182 RCLCPP_DEBUG(get_node()->get_logger(), "Adding predicate '%s'.", predicate_name.c_str());
+
183 }
+
184 try {
+
185 this->predicates_.insert_or_assign(predicate_name, Predicate(predicate_function));
+
186 } catch (const std::exception& ex) {
+ +
188 get_node()->get_logger(), "Failed to evaluate callback of predicate '%s', returning false: %s",
+
189 predicate_name.c_str(), ex.what());
+
190 }
+
191}
+
+
192
+
+
193bool BaseControllerInterface::get_predicate(const std::string& predicate_name) const {
+
194 auto predicate_it = predicates_.find(predicate_name);
+
195 if (predicate_it == predicates_.end()) {
+ +
197 get_node()->get_logger(), *get_node()->get_clock(), 1000,
+
198 "Failed to get predicate '%s': Predicate does not exists, returning false.", predicate_name.c_str());
+
199 return false;
+
200 }
+
201 try {
+
202 return predicate_it->second.get_value();
+
203 } catch (const std::exception& ex) {
+ +
205 get_node()->get_logger(), *get_node()->get_clock(), 1000,
+
206 "Failed to evaluate callback of predicate '%s', returning false: %s", predicate_name.c_str(), ex.what());
+
207 }
+
208 return false;
+
209}
+
+
210
+
+
211void BaseControllerInterface::set_predicate(const std::string& predicate_name, bool predicate_value) {
+
213}
214
-
215void BaseControllerInterface::set_predicate(const std::string& predicate_name, bool predicate_value) {
- -
217}
-
-
218
-
- -
220 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
-
221 auto predicate_it = predicates_.find(predicate_name);
-
222 if (predicate_it == predicates_.end()) {
- -
224 get_node()->get_logger(), *get_node()->get_clock(), 1000,
-
225 "Failed to set predicate '%s': Predicate does not exist.", predicate_name.c_str());
-
226 return;
+ +
216 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
+
217 auto predicate_it = predicates_.find(predicate_name);
+
218 if (predicate_it == predicates_.end()) {
+ +
220 get_node()->get_logger(), *get_node()->get_clock(), 1000,
+
221 "Failed to set predicate '%s': Predicate does not exist.", predicate_name.c_str());
+
222 return;
+
223 }
+
224 predicate_it->second.set_predicate(predicate_function);
+
225 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
+
226 publish_predicate(predicate_name, *new_predicate);
227 }
-
228 predicate_it->second.set_predicate(predicate_function);
-
229 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
-
230 publish_predicate(predicate_name, *new_predicate);
-
231 }
-
232}
-
-
233
-
-
234void BaseControllerInterface::add_trigger(const std::string& trigger_name) {
-
235 if (trigger_name.empty()) {
-
236 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add trigger: Provide a non empty string as a name.");
-
237 return;
-
238 }
-
239 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) != triggers_.cend()) {
- -
241 get_node()->get_logger(), "Failed to add trigger: there is already a trigger with name '%s'.",
-
242 trigger_name.c_str());
-
243 return;
-
244 }
-
245 if (predicates_.find(trigger_name) != predicates_.end()) {
- -
247 get_node()->get_logger(), "Failed to add trigger: there is already a predicate with name '%s'.",
-
248 trigger_name.c_str());
-
249 return;
-
250 }
-
251 triggers_.push_back(trigger_name);
- -
253}
-
-
254
-
-
255void BaseControllerInterface::trigger(const std::string& trigger_name) {
-
256 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) == triggers_.cend()) {
- -
258 get_node()->get_logger(), "Failed to trigger: could not find trigger with name '%s'.", trigger_name.c_str());
-
259 return;
-
260 }
- -
262 // reset the trigger to be published on the next step
-
263 predicates_.at(trigger_name).set_predicate([]() { return false; });
-
264}
-
-
265
-
266modulo_interfaces::msg::Predicate
-
267BaseControllerInterface::get_predicate_message(const std::string& name, bool value) const {
-
268 modulo_interfaces::msg::Predicate message;
-
269 message.predicate = name;
-
270 message.value = value;
-
271 return message;
-
272}
-
273
-
274void BaseControllerInterface::publish_predicate(const std::string& predicate_name, bool value) const {
-
275 auto message(predicate_message_);
-
276 message.predicates.push_back(get_predicate_message(predicate_name, value));
-
277 predicate_publisher_->publish(message);
-
278}
-
279
-
280void BaseControllerInterface::publish_predicates() {
-
281 auto message(predicate_message_);
-
282 for (auto predicate_it = predicates_.begin(); predicate_it != predicates_.end(); ++predicate_it) {
-
283 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
-
284 message.predicates.push_back(get_predicate_message(predicate_it->first, *new_predicate));
-
285 }
-
286 }
-
287 if (message.predicates.size()) {
-
288 predicate_publisher_->publish(message);
-
289 }
-
290}
-
291
-
292std::string BaseControllerInterface::validate_and_declare_signal(
-
293 const std::string& signal_name, const std::string& type, const std::string& default_topic, bool fixed_topic) {
-
294 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
-
295 if (parsed_signal_name.empty()) {
- -
297 get_node()->get_logger(),
-
298 "The parsed signal name for %s '%s' is empty. Provide a string with valid characters for the signal name "
-
299 "([a-zA-Z0-9_]).",
-
300 type.c_str(), signal_name.c_str());
-
301 return "";
-
302 }
- - -
305 get_node()->get_logger(),
-
306 "The parsed signal name for %s '%s' is '%s'. Use the parsed signal name to refer to this %s and its topic "
-
307 "parameter.",
-
308 type.c_str(), signal_name.c_str(), parsed_signal_name.c_str(), type.c_str());
+
228}
+
+
229
+
+
230void BaseControllerInterface::add_trigger(const std::string& trigger_name) {
+
231 if (trigger_name.empty()) {
+
232 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add trigger: Provide a non empty string as a name.");
+
233 return;
+
234 }
+
235 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) != triggers_.cend()) {
+ +
237 get_node()->get_logger(), "Failed to add trigger: there is already a trigger with name '%s'.",
+
238 trigger_name.c_str());
+
239 return;
+
240 }
+
241 if (predicates_.find(trigger_name) != predicates_.end()) {
+ +
243 get_node()->get_logger(), "Failed to add trigger: there is already a predicate with name '%s'.",
+
244 trigger_name.c_str());
+
245 return;
+
246 }
+
247 triggers_.push_back(trigger_name);
+ +
249}
+
+
250
+
+
251void BaseControllerInterface::trigger(const std::string& trigger_name) {
+
252 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) == triggers_.cend()) {
+ +
254 get_node()->get_logger(), "Failed to trigger: could not find trigger with name '%s'.", trigger_name.c_str());
+
255 return;
+
256 }
+ +
258 // reset the trigger to be published on the next step
+
259 predicates_.at(trigger_name).set_predicate([]() { return false; });
+
260}
+
+
261
+
262modulo_interfaces::msg::Predicate
+
263BaseControllerInterface::get_predicate_message(const std::string& name, bool value) const {
+
264 modulo_interfaces::msg::Predicate message;
+
265 message.predicate = name;
+
266 message.value = value;
+
267 return message;
+
268}
+
269
+
270void BaseControllerInterface::publish_predicate(const std::string& predicate_name, bool value) const {
+
271 auto message(predicate_message_);
+
272 message.predicates.push_back(get_predicate_message(predicate_name, value));
+
273 predicate_publisher_->publish(message);
+
274}
+
275
+
276void BaseControllerInterface::publish_predicates() {
+
277 auto message(predicate_message_);
+
278 for (auto predicate_it = predicates_.begin(); predicate_it != predicates_.end(); ++predicate_it) {
+
279 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
+
280 message.predicates.push_back(get_predicate_message(predicate_it->first, *new_predicate));
+
281 }
+
282 }
+
283 if (message.predicates.size()) {
+
284 predicate_publisher_->publish(message);
+
285 }
+
286}
+
287
+
288std::string BaseControllerInterface::validate_and_declare_signal(
+
289 const std::string& signal_name, const std::string& type, const std::string& default_topic, bool fixed_topic) {
+
290 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
+
291 if (parsed_signal_name.empty()) {
+
292 RCLCPP_WARN(
+
293 get_node()->get_logger(),
+
294 "The parsed signal name for %s '%s' is empty. Provide a string with valid characters for the signal name "
+
295 "([a-zA-Z0-9_]).",
+
296 type.c_str(), signal_name.c_str());
+
297 return "";
+
298 }
+
299 if (signal_name != parsed_signal_name) {
+
300 RCLCPP_WARN(
+
301 get_node()->get_logger(),
+
302 "The parsed signal name for %s '%s' is '%s'. Use the parsed signal name to refer to this %s and its topic "
+
303 "parameter.",
+
304 type.c_str(), signal_name.c_str(), parsed_signal_name.c_str(), type.c_str());
+
305 }
+
306 if (inputs_.find(parsed_signal_name) != inputs_.end()) {
+
307 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as input.", parsed_signal_name.c_str());
+
308 return "";
309 }
-
310 if (inputs_.find(parsed_signal_name) != inputs_.end()) {
-
311 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as input.", parsed_signal_name.c_str());
+
310 if (outputs_.find(parsed_signal_name) != outputs_.end()) {
+
311 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as output", parsed_signal_name.c_str());
312 return "";
313 }
-
314 if (outputs_.find(parsed_signal_name) != outputs_.end()) {
-
315 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as output", parsed_signal_name.c_str());
-
316 return "";
-
317 }
-
318 auto topic = default_topic.empty() ? "~/" + parsed_signal_name : default_topic;
-
319 auto parameter_name = parsed_signal_name + "_topic";
-
320 if (get_node()->has_parameter(parameter_name) && get_parameter(parameter_name)->is_empty()) {
-
321 set_parameter_value<std::string>(parameter_name, topic);
-
322 } else {
-
323 add_parameter<std::string>(
-
324 parameter_name, topic, "Signal topic name of " + type + " '" + parsed_signal_name + "'", fixed_topic);
-
325 }
-
326 RCLCPP_DEBUG(
-
327 get_node()->get_logger(), "Declared %s '%s' and parameter '%s' with value '%s'.", type.c_str(),
-
328 parsed_signal_name.c_str(), parameter_name.c_str(), topic.c_str());
-
329 return parsed_signal_name;
-
330}
-
331
-
332void BaseControllerInterface::create_input(
-
333 const ControllerInput& input, const std::string& name, const std::string& topic_name) {
-
334 auto parsed_name = validate_and_declare_signal(name, "input", topic_name);
-
335 if (!parsed_name.empty()) {
-
336 inputs_.insert_or_assign(parsed_name, input);
-
337 }
-
338}
-
339
-
340void BaseControllerInterface::add_inputs() {
-
341 for (auto& [name, input] : inputs_) {
-
342 try {
-
343 auto topic = get_parameter_value<std::string>(name + "_topic");
-
344 std::visit(
-
345 overloaded{
-
346 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<EncodedState>>&) {
-
347 subscriptions_.push_back(create_subscription<EncodedState>(name, topic));
-
348 },
-
349 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>&) {
-
350 subscriptions_.push_back(create_subscription<std_msgs::msg::Bool>(name, topic));
-
351 },
-
352 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>&) {
-
353 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64>(name, topic));
-
354 },
-
355 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>&) {
-
356 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64MultiArray>(name, topic));
-
357 },
-
358 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>&) {
-
359 subscriptions_.push_back(create_subscription<std_msgs::msg::Int32>(name, topic));
-
360 },
-
361 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>&) {
-
362 subscriptions_.push_back(create_subscription<std_msgs::msg::String>(name, topic));
-
363 },
-
364 [&](const std::any&) {
-
365 custom_input_configuration_callables_.at(name)(name, topic);
-
366 }},
-
367 input.buffer);
-
368 } catch (const std::exception& ex) {
-
369 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add input '%s': %s", name.c_str(), ex.what());
-
370 }
-
371 }
-
372}
-
373
-
374void BaseControllerInterface::create_output(
-
375 const PublisherVariant& publishers, const std::string& name, const std::string& topic_name) {
-
376 auto parsed_name = validate_and_declare_signal(name, "output", topic_name);
-
377 if (!parsed_name.empty()) {
-
378 outputs_.insert_or_assign(parsed_name, publishers);
-
379 }
-
380}
-
381
-
382void BaseControllerInterface::add_outputs() {
-
383 for (auto& [name, publishers] : outputs_) {
-
384 try {
-
385 auto topic = get_parameter_value<std::string>(name + "_topic");
-
386 std::visit(
-
387 overloaded{
-
388 [&](EncodedStatePublishers& pub) {
-
389 std::get<1>(pub) = get_node()->create_publisher<EncodedState>(topic, qos_);
-
390 std::get<2>(pub) = std::make_shared<realtime_tools::RealtimePublisher<EncodedState>>(std::get<1>(pub));
+
314 auto topic = default_topic.empty() ? "~/" + parsed_signal_name : default_topic;
+
315 auto parameter_name = parsed_signal_name + "_topic";
+
316 if (get_node()->has_parameter(parameter_name) && get_parameter(parameter_name)->is_empty()) {
+
317 set_parameter_value<std::string>(parameter_name, topic);
+
318 } else {
+
319 add_parameter<std::string>(
+
320 parameter_name, topic, "Signal topic name of " + type + " '" + parsed_signal_name + "'", fixed_topic);
+
321 }
+
322 RCLCPP_DEBUG(
+
323 get_node()->get_logger(), "Declared %s '%s' and parameter '%s' with value '%s'.", type.c_str(),
+
324 parsed_signal_name.c_str(), parameter_name.c_str(), topic.c_str());
+
325 return parsed_signal_name;
+
326}
+
327
+
328void BaseControllerInterface::create_input(
+
329 const ControllerInput& input, const std::string& name, const std::string& topic_name) {
+
330 auto parsed_name = validate_and_declare_signal(name, "input", topic_name);
+
331 if (!parsed_name.empty()) {
+
332 inputs_.insert_or_assign(parsed_name, input);
+
333 }
+
334}
+
335
+
336void BaseControllerInterface::add_inputs() {
+
337 for (auto& [name, input] : inputs_) {
+
338 try {
+
339 auto topic = get_parameter_value<std::string>(name + "_topic");
+
340 std::visit(
+
341 overloaded{
+
342 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<EncodedState>>&) {
+
343 subscriptions_.push_back(create_subscription<EncodedState>(name, topic));
+
344 },
+
345 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>&) {
+
346 subscriptions_.push_back(create_subscription<std_msgs::msg::Bool>(name, topic));
+
347 },
+
348 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>&) {
+
349 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64>(name, topic));
+
350 },
+
351 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>&) {
+
352 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64MultiArray>(name, topic));
+
353 },
+
354 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>&) {
+
355 subscriptions_.push_back(create_subscription<std_msgs::msg::Int32>(name, topic));
+
356 },
+
357 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>&) {
+
358 subscriptions_.push_back(create_subscription<std_msgs::msg::String>(name, topic));
+
359 },
+
360 [&](const std::any&) {
+
361 custom_input_configuration_callables_.at(name)(name, topic);
+
362 }},
+
363 input.buffer);
+
364 } catch (const std::exception& ex) {
+
365 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add input '%s': %s", name.c_str(), ex.what());
+
366 }
+
367 }
+
368}
+
369
+
370void BaseControllerInterface::create_output(
+
371 const PublisherVariant& publishers, const std::string& name, const std::string& topic_name) {
+
372 auto parsed_name = validate_and_declare_signal(name, "output", topic_name);
+
373 if (!parsed_name.empty()) {
+
374 outputs_.insert_or_assign(parsed_name, publishers);
+
375 }
+
376}
+
377
+
378void BaseControllerInterface::add_outputs() {
+
379 for (auto& [name, publishers] : outputs_) {
+
380 try {
+
381 auto topic = get_parameter_value<std::string>(name + "_topic");
+
382 std::visit(
+
383 overloaded{
+
384 [&](EncodedStatePublishers& pub) {
+
385 std::get<1>(pub) = get_node()->create_publisher<EncodedState>(topic, qos_);
+
386 std::get<2>(pub) = std::make_shared<realtime_tools::RealtimePublisher<EncodedState>>(std::get<1>(pub));
+
387 },
+
388 [&](BoolPublishers& pub) {
+
389 pub.first = get_node()->create_publisher<std_msgs::msg::Bool>(topic, qos_);
+
390 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>(pub.first);
391 },
-
392 [&](BoolPublishers& pub) {
-
393 pub.first = get_node()->create_publisher<std_msgs::msg::Bool>(topic, qos_);
-
394 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>(pub.first);
+
392 [&](DoublePublishers& pub) {
+
393 pub.first = get_node()->create_publisher<std_msgs::msg::Float64>(topic, qos_);
+
394 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64>>(pub.first);
395 },
-
396 [&](DoublePublishers& pub) {
-
397 pub.first = get_node()->create_publisher<std_msgs::msg::Float64>(topic, qos_);
-
398 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64>>(pub.first);
-
399 },
-
400 [&](DoubleVecPublishers& pub) {
-
401 pub.first = get_node()->create_publisher<std_msgs::msg::Float64MultiArray>(topic, qos_);
-
402 pub.second =
-
403 std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64MultiArray>>(pub.first);
+
396 [&](DoubleVecPublishers& pub) {
+
397 pub.first = get_node()->create_publisher<std_msgs::msg::Float64MultiArray>(topic, qos_);
+
398 pub.second =
+
399 std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64MultiArray>>(pub.first);
+
400 },
+
401 [&](IntPublishers& pub) {
+
402 pub.first = get_node()->create_publisher<std_msgs::msg::Int32>(topic, qos_);
+
403 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Int32>>(pub.first);
404 },
-
405 [&](IntPublishers& pub) {
-
406 pub.first = get_node()->create_publisher<std_msgs::msg::Int32>(topic, qos_);
-
407 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Int32>>(pub.first);
+
405 [&](StringPublishers& pub) {
+
406 pub.first = get_node()->create_publisher<std_msgs::msg::String>(topic, qos_);
+
407 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::String>>(pub.first);
408 },
-
409 [&](StringPublishers& pub) {
-
410 pub.first = get_node()->create_publisher<std_msgs::msg::String>(topic, qos_);
-
411 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::String>>(pub.first);
-
412 },
-
413 [&](CustomPublishers& pub) {
-
414 custom_output_configuration_callables_.at(name)(pub, name);
-
415 }},
-
416 publishers);
-
417 } catch (const std::bad_any_cast& ex) {
-
418 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add custom output '%s': %s", name.c_str(), ex.what());
-
419 } catch (const std::exception& ex) {
-
420 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add output '%s': %s", name.c_str(), ex.what());
-
421 }
-
422 }
+
409 [&](CustomPublishers& pub) {
+
410 custom_output_configuration_callables_.at(name)(pub, name);
+
411 }},
+
412 publishers);
+
413 } catch (const std::bad_any_cast& ex) {
+
414 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add custom output '%s': %s", name.c_str(), ex.what());
+
415 } catch (const std::exception& ex) {
+
416 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add output '%s': %s", name.c_str(), ex.what());
+
417 }
+
418 }
+
419}
+
420
+
+
421void BaseControllerInterface::set_input_validity_period(double input_validity_period) {
+
422 input_validity_period_ = input_validity_period;
423}
-
424
-
-
425void BaseControllerInterface::set_input_validity_period(double input_validity_period) {
-
426 input_validity_period_ = input_validity_period;
-
427}
-
428
-
429bool BaseControllerInterface::check_input_valid(const std::string& name) const {
-
430 if (inputs_.find(name) == inputs_.end()) {
- -
432 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Could not find input '%s'", name.c_str());
-
433 return false;
-
434 }
-
435 if (static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
-
436 std::chrono::steady_clock::now() - inputs_.at(name).timestamp)
-
437 .count())
-
438 / 1e9
-
439 >= input_validity_period_) {
-
440 return false;
-
441 }
-
442 return true;
-
443}
-
444
-
445std::string
-
446BaseControllerInterface::validate_service_name(const std::string& service_name, const std::string& type) const {
-
447 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
-
448 if (parsed_service_name.empty()) {
- -
450 get_node()->get_logger(),
-
451 "The parsed service name for %s service '%s' is empty. Provide a string with valid characters for the service "
-
452 "name "
-
453 "([a-zA-Z0-9_]).",
-
454 type.c_str(), service_name.c_str());
-
455 return "";
-
456 }
- - -
459 get_node()->get_logger(),
-
460 "The parsed name for '%s' service '%s' is '%s'. Use the parsed name to refer to this service.", type.c_str(),
-
461 service_name.c_str(), parsed_service_name.c_str());
-
462 }
-
463 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
- -
465 get_node()->get_logger(), "Service with name '%s' already exists as empty service.",
-
466 parsed_service_name.c_str());
-
467 return "";
-
468 }
-
469 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
- -
471 get_node()->get_logger(), "Service with name '%s' already exists as string service.",
-
472 parsed_service_name.c_str());
-
473 return "";
-
474 }
-
475 RCLCPP_DEBUG(get_node()->get_logger(), "Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
-
476 return parsed_service_name;
-
477}
-
478
-
- -
480 const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback) {
-
481 auto parsed_service_name = validate_service_name(service_name, "empty");
-
482 if (!parsed_service_name.empty()) {
-
483 try {
-
484 auto service = get_node()->create_service<modulo_interfaces::srv::EmptyTrigger>(
-
485 "~/" + parsed_service_name,
-
486 [this, callback](
-
487 const std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Request>,
-
488 std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Response> response) {
-
489 try {
-
490 if (this->command_mutex_.try_lock_for(100ms)) {
- -
492 this->command_mutex_.unlock();
-
493 response->success = callback_response.success;
-
494 response->message = callback_response.message;
-
495 } else {
-
496 response->success = false;
-
497 response->message = "Unable to acquire lock for command interface within 100ms";
-
498 }
-
499 } catch (const std::exception& ex) {
-
500 response->success = false;
-
501 response->message = ex.what();
-
502 }
-
503 },
-
504 qos_);
-
505 empty_services_.insert_or_assign(parsed_service_name, service);
-
506 } catch (const std::exception& ex) {
-
507 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
-
508 }
-
509 }
-
510}
-
-
511
-
- -
513 const std::string& service_name,
-
514 const std::function<ControllerServiceResponse(const std::string& string)>& callback) {
-
515 auto parsed_service_name = validate_service_name(service_name, "string");
-
516 if (!parsed_service_name.empty()) {
-
517 try {
-
518 auto service = get_node()->create_service<modulo_interfaces::srv::StringTrigger>(
-
519 "~/" + parsed_service_name,
-
520 [this, callback](
-
521 const std::shared_ptr<modulo_interfaces::srv::StringTrigger::Request> request,
-
522 std::shared_ptr<modulo_interfaces::srv::StringTrigger::Response> response) {
-
523 try {
-
524 if (this->command_mutex_.try_lock_for(100ms)) {
-
525 auto callback_response = callback(request->payload);
-
526 this->command_mutex_.unlock();
-
527 response->success = callback_response.success;
-
528 response->message = callback_response.message;
-
529 } else {
-
530 response->success = false;
-
531 response->message = "Unable to acquire lock for command interface within 100ms";
-
532 }
-
533 } catch (const std::exception& ex) {
-
534 response->success = false;
-
535 response->message = ex.what();
-
536 }
-
537 },
-
538 qos_);
-
539 string_services_.insert_or_assign(parsed_service_name, service);
-
540 } catch (const std::exception& ex) {
-
541 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
-
542 }
-
543 }
+
424
+
425bool BaseControllerInterface::check_input_valid(const std::string& name) const {
+
426 if (inputs_.find(name) == inputs_.end()) {
+ +
428 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Could not find input '%s'", name.c_str());
+
429 return false;
+
430 }
+
431 if (static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
+
432 std::chrono::steady_clock::now() - inputs_.at(name).timestamp)
+
433 .count())
+
434 / 1e9
+
435 >= input_validity_period_) {
+
436 return false;
+
437 }
+
438 return true;
+
439}
+
440
+
441std::string
+
442BaseControllerInterface::validate_service_name(const std::string& service_name, const std::string& type) const {
+
443 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
+
444 if (parsed_service_name.empty()) {
+ +
446 get_node()->get_logger(),
+
447 "The parsed service name for %s service '%s' is empty. Provide a string with valid characters for the service "
+
448 "name "
+
449 "([a-zA-Z0-9_]).",
+
450 type.c_str(), service_name.c_str());
+
451 return "";
+
452 }
+ + +
455 get_node()->get_logger(),
+
456 "The parsed name for '%s' service '%s' is '%s'. Use the parsed name to refer to this service.", type.c_str(),
+
457 service_name.c_str(), parsed_service_name.c_str());
+
458 }
+
459 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
+ +
461 get_node()->get_logger(), "Service with name '%s' already exists as empty service.",
+
462 parsed_service_name.c_str());
+
463 return "";
+
464 }
+
465 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
+ +
467 get_node()->get_logger(), "Service with name '%s' already exists as string service.",
+
468 parsed_service_name.c_str());
+
469 return "";
+
470 }
+
471 RCLCPP_DEBUG(get_node()->get_logger(), "Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
+
472 return parsed_service_name;
+
473}
+
474
+
+ +
476 const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback) {
+
477 auto parsed_service_name = validate_service_name(service_name, "empty");
+
478 if (!parsed_service_name.empty()) {
+
479 try {
+
480 auto service = get_node()->create_service<modulo_interfaces::srv::EmptyTrigger>(
+
481 "~/" + parsed_service_name,
+
482 [this, callback](
+
483 const std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Request>,
+
484 std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Response> response) {
+
485 try {
+
486 if (this->command_mutex_.try_lock_for(100ms)) {
+ +
488 this->command_mutex_.unlock();
+
489 response->success = callback_response.success;
+
490 response->message = callback_response.message;
+
491 } else {
+
492 response->success = false;
+
493 response->message = "Unable to acquire lock for command interface within 100ms";
+
494 }
+
495 } catch (const std::exception& ex) {
+
496 response->success = false;
+
497 response->message = ex.what();
+
498 }
+
499 },
+
500 qos_);
+
501 empty_services_.insert_or_assign(parsed_service_name, service);
+
502 } catch (const std::exception& ex) {
+
503 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
+
504 }
+
505 }
+
506}
+
+
507
+
+ +
509 const std::string& service_name,
+
510 const std::function<ControllerServiceResponse(const std::string& string)>& callback) {
+
511 auto parsed_service_name = validate_service_name(service_name, "string");
+
512 if (!parsed_service_name.empty()) {
+
513 try {
+
514 auto service = get_node()->create_service<modulo_interfaces::srv::StringTrigger>(
+
515 "~/" + parsed_service_name,
+
516 [this, callback](
+
517 const std::shared_ptr<modulo_interfaces::srv::StringTrigger::Request> request,
+
518 std::shared_ptr<modulo_interfaces::srv::StringTrigger::Response> response) {
+
519 try {
+
520 if (this->command_mutex_.try_lock_for(100ms)) {
+
521 auto callback_response = callback(request->payload);
+
522 this->command_mutex_.unlock();
+
523 response->success = callback_response.success;
+
524 response->message = callback_response.message;
+
525 } else {
+
526 response->success = false;
+
527 response->message = "Unable to acquire lock for command interface within 100ms";
+
528 }
+
529 } catch (const std::exception& ex) {
+
530 response->success = false;
+
531 response->message = ex.what();
+
532 }
+
533 },
+
534 qos_);
+
535 string_services_.insert_or_assign(parsed_service_name, service);
+
536 } catch (const std::exception& ex) {
+
537 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add service '%s': %s", parsed_service_name.c_str(), ex.what());
+
538 }
+
539 }
+
540}
+
+
541
+
+ +
543 return qos_;
544}
545
- -
547 if (!is_node_initialized()) {
-
548 throw modulo_core::exceptions::CoreException("Failed to add TF buffer and listener: Node is not initialized yet.");
-
549 }
-
550 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
-
551 RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding TF buffer and listener.");
-
552 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
-
553 this->tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_node()->get_clock());
-
554 this->tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*this->tf_buffer_);
-
555 } else {
-
556 RCLCPP_DEBUG(this->get_node()->get_logger(), "TF buffer and listener already exist.");
-
557 }
-
558}
-
-
559
-
-
560state_representation::CartesianPose BaseControllerInterface::lookup_transform(
-
561 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
-
562 const tf2::Duration& duration) {
-
563 auto transform = this->lookup_ros_transform(frame, reference_frame, time_point, duration);
-
564 state_representation::CartesianPose result(frame, reference_frame);
- -
566 return result;
-
567}
-
-
568
-
-
569state_representation::CartesianPose BaseControllerInterface::lookup_transform(
-
570 const std::string& frame, const std::string& reference_frame, double validity_period,
-
571 const tf2::Duration& duration) {
-
572 auto transform =
-
573 this->lookup_ros_transform(frame, reference_frame, tf2::TimePoint(std::chrono::microseconds(0)), duration);
-
574 if (validity_period > 0.0
-
575 && (this->get_node()->get_clock()->now() - transform.header.stamp).seconds() > validity_period) {
-
576 throw modulo_core::exceptions::LookupTransformException("Failed to lookup transform: Latest transform is too old!");
-
577 }
-
578 state_representation::CartesianPose result(frame, reference_frame);
- -
580 return result;
-
581}
-
-
582
-
583geometry_msgs::msg::TransformStamped BaseControllerInterface::lookup_ros_transform(
-
584 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
-
585 const tf2::Duration& duration) {
-
586 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
- -
588 "Failed to lookup transform: No TF buffer / listener configured.");
-
589 }
-
590 try {
-
591 return this->tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration);
-
592 } catch (const tf2::TransformException& ex) {
- -
594 std::string("Failed to lookup transform: ").append(ex.what()));
-
595 }
-
596}
-
597
-
- -
599 if (!is_node_initialized()) {
-
600 throw modulo_core::exceptions::CoreException("Failed to add TF broadcaster: Node is not initialized yet.");
-
601 }
-
602 if (this->tf_broadcaster_ == nullptr) {
-
603 RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding TF broadcaster.");
-
604 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
-
605 this->tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(get_node());
-
606 } else {
-
607 RCLCPP_DEBUG(this->get_node()->get_logger(), "TF broadcaster already exists.");
-
608 }
-
609}
-
-
610
-
- -
612 if (!is_node_initialized()) {
-
613 throw modulo_core::exceptions::CoreException("Failed to add static TF broadcaster: Node is not initialized yet.");
-
614 }
-
615 if (this->static_tf_broadcaster_ == nullptr) {
-
616 RCLCPP_DEBUG(this->get_node()->get_logger(), "Adding static TF broadcaster.");
-
617 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
-
618 this->static_tf_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(get_node());
-
619 } else {
-
620 RCLCPP_DEBUG(this->get_node()->get_logger(), "Static TF broadcaster already exists.");
-
621 }
-
622}
-
-
623
-
-
624void BaseControllerInterface::send_transform(const state_representation::CartesianPose& transform) {
-
625 this->send_transforms(std::vector<state_representation::CartesianPose>{transform});
-
626}
-
-
627
-
-
628void BaseControllerInterface::send_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
-
629 this->publish_transforms(transforms, this->tf_broadcaster_);
-
630}
-
-
631
-
-
632void BaseControllerInterface::send_static_transform(const state_representation::CartesianPose& transform) {
-
633 this->send_static_transforms(std::vector<state_representation::CartesianPose>{transform});
-
634}
-
-
635
-
- -
637 const std::vector<state_representation::CartesianPose>& transforms) {
-
638 this->publish_transforms(transforms, this->static_tf_broadcaster_, true);
-
639}
-
-
640
-
- -
642 return qos_;
-
643}
-
-
644
-
-
645void BaseControllerInterface::set_qos(const rclcpp::QoS& qos) {
-
646 qos_ = qos;
-
647}
-
-
648
-
- -
650 return get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
-
651}
-
-
652
-
- -
654 return command_mutex_;
-
655}
-
-
656
-
- -
658 try {
-
659 get_node();
-
660 return true;
-
661 } catch (const std::runtime_error&) {
-
662 return false;
-
663 }
-
664}
-
-
665
-
666}// namespace modulo_controllers
-
void send_static_transform(const state_representation::CartesianPose &transform)
Send a static transform to TF.
-
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
Add signals.
-
void add_static_tf_broadcaster()
Configure a static transform broadcaster.
-
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
-
void send_static_transforms(const std::vector< state_representation::CartesianPose > &transforms)
Send a vector of static transforms to TF.
-
state_representation::CartesianPose lookup_transform(const std::string &frame, const std::string &reference_frame, const tf2::TimePoint &time_point, const tf2::Duration &duration)
Look up a transform from TF.
-
void add_tf_broadcaster()
Configure a transform broadcaster.
-
bool is_active() const
Check if the controller is currently in state active or not.
-
void send_transform(const state_representation::CartesianPose &transform)
Send a transform to TF.
-
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
-
void set_input_validity_period(double input_validity_period)
Set the input validity period of input signals.
-
CallbackReturn on_init() override
Declare parameters and register the on_set_parameters callback.
+
546void BaseControllerInterface::set_qos(const rclcpp::QoS& qos) {
+
547 qos_ = qos;
+
548}
+
+
549
+
+ +
551 return get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
+
552}
+
+
553
+
+ +
555 return command_mutex_;
+
556}
+
+
557
+
558}// namespace modulo_controllers
+
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
+
CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
Add signals.
+
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
+
bool is_active() const
Check if the controller is currently in state active or not.
+
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
+
void set_input_validity_period(double input_validity_period)
Set the input validity period of input signals.
+
CallbackReturn on_init() override
Declare parameters and register the on_set_parameters callback.
void add_parameter(const std::shared_ptr< state_representation::ParameterInterface > &parameter, const std::string &description, bool read_only=false)
Add a parameter.
-
void trigger(const std::string &trigger_name)
Latch the trigger with the provided name.
-
void set_qos(const rclcpp::QoS &qos)
Set the Quality of Service for ROS publishers and subscribers.
-
void add_tf_listener()
Configure a transform buffer and listener.
-
void set_predicate(const std::string &predicate_name, bool predicate_value)
Set the value of the predicate given as parameter, if the predicate is not found does not do anything...
-
void add_predicate(const std::string &predicate_name, bool predicate_value)
Add a predicate to the map of predicates.
-
bool get_predicate(const std::string &predicate_name) const
Get the logical value of a predicate.
-
bool is_node_initialized() const
Check if the node has been initialized or not.
-
virtual bool on_validate_parameter_callback(const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Parameter validation function to be redefined by derived controller classes.
- -
void add_service(const std::string &service_name, const std::function< ControllerServiceResponse(void)> &callback)
Add a service to trigger a callback function with no input arguments.
-
std::timed_mutex & get_command_mutex()
Get the reference to the command mutex.
-
void add_trigger(const std::string &trigger_name)
Add a trigger to the controller.
-
void send_transforms(const std::vector< state_representation::CartesianPose > &transforms)
Send a vector of transforms to TF.
+
void trigger(const std::string &trigger_name)
Latch the trigger with the provided name.
+
void set_qos(const rclcpp::QoS &qos)
Set the Quality of Service for ROS publishers and subscribers.
+
void set_predicate(const std::string &predicate_name, bool predicate_value)
Set the value of the predicate given as parameter, if the predicate is not found does not do anything...
+
void add_predicate(const std::string &predicate_name, bool predicate_value)
Add a predicate to the map of predicates.
+
bool get_predicate(const std::string &predicate_name) const
Get the logical value of a predicate.
+
virtual bool on_validate_parameter_callback(const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Parameter validation function to be redefined by derived controller classes.
+ +
void add_service(const std::string &service_name, const std::function< ControllerServiceResponse(void)> &callback)
Add a service to trigger a callback function with no input arguments.
+
std::timed_mutex & get_command_mutex()
Get the reference to the command mutex.
+
void add_trigger(const std::string &trigger_name)
Add a trigger to the controller.
-
A base class for all core exceptions.
-
An exception class to notify an error while looking up TF transforms.
An exception class to notify errors with parameters in modulo classes.
An exception class to notify incompatibility when translating parameters from different sources.
rclcpp::Parameter write_parameter(const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Write a ROS Parameter from a ParameterInterface pointer.
rclcpp::ParameterType get_ros_parameter_type(const state_representation::ParameterType &parameter_type)
Given a state representation parameter type, get the corresponding ROS parameter type.
void copy_parameter_value(const std::shared_ptr< const state_representation::ParameterInterface > &source_parameter, const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Copy the value of one parameter interface into another.
-
void read_message(state_representation::CartesianState &state, const geometry_msgs::msg::Accel &message)
Convert a ROS geometry_msgs::msg::Accel to a CartesianState.
std::shared_ptr< state_representation::ParameterInterface > read_parameter_const(const rclcpp::Parameter &ros_parameter, const std::shared_ptr< const state_representation::ParameterInterface > &parameter)
Update the parameter value of a ParameterInterface from a ROS Parameter object only if the two parame...
Modulo Core.
-
Response structure to be returned by controller services.
+
Response structure to be returned by controller services.