Modulo 5.0.0
Loading...
Searching...
No Matches
BaseControllerInterface.cpp
1#include "modulo_controllers/BaseControllerInterface.hpp"
2
3#include <console_bridge/console.h>
4
5#include <lifecycle_msgs/msg/state.hpp>
6
7#include <modulo_core/exceptions.hpp>
8#include <modulo_core/translators/message_readers.hpp>
9
10template<class... Ts>
11struct overloaded : Ts... {
12 using Ts::operator()...;
13};
14template<class... Ts>
15overloaded(Ts...) -> overloaded<Ts...>;
16
17using namespace modulo_core;
18using namespace state_representation;
19using namespace std::chrono_literals;
20
21namespace modulo_controllers {
22
24 : controller_interface::ControllerInterface(), input_validity_period_(std::numeric_limits<double>::quiet_NaN()) {}
25
26rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn BaseControllerInterface::on_init() {
27 // registering set_parameter callbacks is only possible on_init since the lifecycle node is not yet initialized
28 // on construction. This means we might not be able to validate parameter overrides - if they are provided.
29 pre_set_parameter_cb_handle_ = get_node()->add_pre_set_parameters_callback(
30 [this](std::vector<rclcpp::Parameter>& parameters) { return this->pre_set_parameters_callback(parameters); });
31 on_set_parameter_cb_handle_ = get_node()->add_on_set_parameters_callback(
32 [this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
33 return this->on_set_parameters_callback(parameters);
34 });
35
36 // these two parameters are declared in the ControllerInterface, need to add them in the internal map as well
37 parameter_map_.set_parameter(std::make_shared<Parameter<int>>("update_rate"));
38 read_only_parameters_.insert_or_assign("update_rate", false);
39 parameter_map_.set_parameter(std::make_shared<Parameter<bool>>("is_async", false));
40 read_only_parameters_.insert_or_assign("is_async", false);
41
42 add_parameter<double>("predicate_publishing_rate", 10.0, "The rate at which to publish controller predicates");
44 "input_validity_period", 1.0, "The maximum age of an input state before discarding it as expired");
45 return CallbackReturn::SUCCESS;
46}
47
48rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
49BaseControllerInterface::on_configure(const rclcpp_lifecycle::State&) {
50 input_validity_period_ = get_parameter_value<double>("input_validity_period");
51 add_inputs();
52 add_outputs();
53
54 if (predicates_.size()) {
55 predicate_publisher_ =
56 get_node()->create_publisher<modulo_interfaces::msg::PredicateCollection>("/predicates", qos_);
57 predicate_message_.node = get_node()->get_fully_qualified_name();
58
59 predicate_timer_ = get_node()->create_wall_timer(
60 std::chrono::nanoseconds(static_cast<int64_t>(1e9 / get_parameter_value<double>("predicate_publishing_rate"))),
61 [this]() { this->publish_predicates(); });
62 }
63 if (assignments_map_.get_parameters().size()) {
64 assignment_publisher_ = get_node()->create_publisher<modulo_interfaces::msg::Assignment>("/assignments", qos_);
65 }
66
67 RCLCPP_DEBUG(get_node()->get_logger(), "Configuration of BaseControllerInterface successful");
68 return CallbackReturn::SUCCESS;
69}
70
72 const std::shared_ptr<ParameterInterface>& parameter, const std::string& description, bool read_only) {
73 rclcpp::Parameter ros_param;
74 try {
75 ros_param = translators::write_parameter(parameter);
77 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
78 }
79 if (!get_node()->has_parameter(parameter->get_name())) {
80 RCLCPP_DEBUG(get_node()->get_logger(), "Adding parameter '%s'.", parameter->get_name().c_str());
81 parameter_map_.set_parameter(parameter);
82 read_only_parameters_.insert_or_assign(parameter->get_name(), false);
83 try {
84 rcl_interfaces::msg::ParameterDescriptor descriptor;
85 descriptor.description = description;
86 descriptor.read_only = read_only;
87 // since the pre_set_parameters_callback is not called on parameter declaration, this has to be true
88 set_parameters_result_.successful = true;
89 set_parameters_result_.reason = "";
90 if (parameter->is_empty()) {
91 descriptor.dynamic_typing = true;
92 descriptor.type = translators::get_ros_parameter_type(parameter->get_parameter_type());
93 get_node()->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
94 } else {
95 get_node()->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
96 }
97 std::vector<rclcpp::Parameter> ros_parameters{get_node()->get_parameters({parameter->get_name()})};
98 pre_set_parameters_callback(ros_parameters);
99 auto result = on_set_parameters_callback(ros_parameters);
100 if (!result.successful) {
101 get_node()->undeclare_parameter(parameter->get_name());
103 }
104 read_only_parameters_.at(parameter->get_name()) = read_only;
105 } catch (const std::exception& ex) {
106 parameter_map_.remove_parameter(parameter->get_name());
107 read_only_parameters_.erase(parameter->get_name());
108 throw modulo_core::exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
109 }
110 } else {
111 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' already exists.", parameter->get_name().c_str());
112 }
113}
114
115std::shared_ptr<ParameterInterface> BaseControllerInterface::get_parameter(const std::string& name) const {
116 try {
117 return parameter_map_.get_parameter(name);
118 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
119 throw modulo_core::exceptions::ParameterException("Failed to get parameter '" + name + "': " + ex.what());
120 }
121}
122
123void BaseControllerInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
124 if (pre_set_parameter_callback_called_) {
125 pre_set_parameter_callback_called_ = false;
126 return;
127 }
128 rcl_interfaces::msg::SetParametersResult result;
129 result.successful = true;
130 for (auto& ros_parameter : parameters) {
131 try {
132 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
133 if (read_only_parameters_.at(ros_parameter.get_name())) {
134 RCLCPP_DEBUG(get_node()->get_logger(), "Parameter '%s' is read only.", ros_parameter.get_name().c_str());
135 continue;
136 }
137
138 // convert the ROS parameter into a ParameterInterface without modifying the original
139 auto new_parameter = translators::read_parameter_const(ros_parameter, parameter);
140 if (!validate_parameter(new_parameter)) {
141 result.successful = false;
142 result.reason += "Validation of parameter '" + ros_parameter.get_name() + "' returned false!";
143 } else if (!new_parameter->is_empty()) {
144 // update the value of the parameter in the map
145 translators::copy_parameter_value(new_parameter, parameter);
146 ros_parameter = translators::write_parameter(new_parameter);
147 }
148 } catch (const std::exception& ex) {
149 result.successful = false;
150 result.reason += ex.what();
151 }
152 }
153 set_parameters_result_ = result;
154}
155
156rcl_interfaces::msg::SetParametersResult
157BaseControllerInterface::on_set_parameters_callback(const std::vector<rclcpp::Parameter>&) {
158 auto result = set_parameters_result_;
159 set_parameters_result_.successful = true;
160 set_parameters_result_.reason = "";
161 return result;
162}
163
164bool BaseControllerInterface::validate_parameter(const std::shared_ptr<ParameterInterface>& parameter) {
165 if (parameter->get_name() == "predicate_publishing_rate" || parameter->get_name() == "input_validity_period") {
166 auto value = parameter->get_parameter_value<double>();
167 if (value <= 0.0 || value > std::numeric_limits<double>::max()) {
168 RCLCPP_ERROR(
169 get_node()->get_logger(), "Value of of parameter '%s' should be greater than 0",
170 parameter->get_name().c_str());
171 return false;
172 }
173 }
174 return on_validate_parameter_callback(parameter);
175}
176
177bool BaseControllerInterface::on_validate_parameter_callback(const std::shared_ptr<ParameterInterface>&) {
178 return true;
179}
180
181void BaseControllerInterface::add_predicate(const std::string& predicate_name, bool predicate_value) {
182 add_predicate(predicate_name, [predicate_value]() { return predicate_value; });
183}
184
186 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
187 if (predicate_name.empty()) {
188 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add predicate: Provide a non empty string as a name.");
189 return;
190 }
191 if (predicates_.find(predicate_name) != predicates_.end()) {
192 RCLCPP_WARN(
193 get_node()->get_logger(), "Predicate with name '%s' already exists, overwriting.", predicate_name.c_str());
194 } else {
195 RCLCPP_DEBUG(get_node()->get_logger(), "Adding predicate '%s'.", predicate_name.c_str());
196 }
197 try {
198 predicates_.insert_or_assign(predicate_name, Predicate(predicate_function));
199 } catch (const std::exception& ex) {
200 RCLCPP_ERROR(
201 get_node()->get_logger(), "Failed to evaluate callback of predicate '%s', returning false: %s",
202 predicate_name.c_str(), ex.what());
203 }
204}
205
206bool BaseControllerInterface::get_predicate(const std::string& predicate_name) const {
207 auto predicate_it = predicates_.find(predicate_name);
208 if (predicate_it == predicates_.end()) {
209 RCLCPP_ERROR_THROTTLE(
210 get_node()->get_logger(), *get_node()->get_clock(), 1000,
211 "Failed to get predicate '%s': Predicate does not exists, returning false.", predicate_name.c_str());
212 return false;
213 }
214 try {
215 return predicate_it->second.get_value();
216 } catch (const std::exception& ex) {
217 RCLCPP_ERROR_THROTTLE(
218 get_node()->get_logger(), *get_node()->get_clock(), 1000,
219 "Failed to evaluate callback of predicate '%s', returning false: %s", predicate_name.c_str(), ex.what());
220 }
221 return false;
222}
223
224void BaseControllerInterface::set_predicate(const std::string& predicate_name, bool predicate_value) {
225 set_predicate(predicate_name, [predicate_value]() { return predicate_value; });
226}
227
229 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
230 auto predicate_it = predicates_.find(predicate_name);
231 if (predicate_it == predicates_.end()) {
232 RCLCPP_ERROR_THROTTLE(
233 get_node()->get_logger(), *get_node()->get_clock(), 1000,
234 "Failed to set predicate '%s': Predicate does not exist.", predicate_name.c_str());
235 return;
236 }
237 predicate_it->second.set_predicate(predicate_function);
238 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
239 publish_predicate(predicate_name, *new_predicate);
240 }
241}
242
243void BaseControllerInterface::add_trigger(const std::string& trigger_name) {
244 if (trigger_name.empty()) {
245 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add trigger: Provide a non empty string as a name.");
246 return;
247 }
248 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) != triggers_.cend()) {
249 RCLCPP_ERROR(
250 get_node()->get_logger(), "Failed to add trigger: there is already a trigger with name '%s'.",
251 trigger_name.c_str());
252 return;
253 }
254 if (predicates_.find(trigger_name) != predicates_.end()) {
255 RCLCPP_ERROR(
256 get_node()->get_logger(), "Failed to add trigger: there is already a predicate with name '%s'.",
257 trigger_name.c_str());
258 return;
259 }
260 triggers_.push_back(trigger_name);
261 add_predicate(trigger_name, false);
262}
263
264void BaseControllerInterface::trigger(const std::string& trigger_name) {
265 if (std::find(triggers_.cbegin(), triggers_.cend(), trigger_name) == triggers_.cend()) {
266 RCLCPP_ERROR(
267 get_node()->get_logger(), "Failed to trigger: could not find trigger with name '%s'.", trigger_name.c_str());
268 return;
269 }
270 set_predicate(trigger_name, true);
271 // reset the trigger to be published on the next step
272 predicates_.at(trigger_name).set_predicate([]() { return false; });
273}
274
275modulo_interfaces::msg::Predicate
276BaseControllerInterface::get_predicate_message(const std::string& name, bool value) const {
277 modulo_interfaces::msg::Predicate message;
278 message.predicate = name;
279 message.value = value;
280 return message;
281}
282
283void BaseControllerInterface::publish_predicate(const std::string& predicate_name, bool value) const {
284 if (predicate_publisher_ == nullptr) {
285 RCLCPP_ERROR_STREAM_THROTTLE(
286 get_node()->get_logger(), *get_node()->get_clock(), 1000,
287 "No predicate publisher configured. Make sure to add predicates `on_init` of the controller.");
288 return;
289 }
290 auto message(predicate_message_);
291 message.predicates.push_back(get_predicate_message(predicate_name, value));
292 predicate_publisher_->publish(message);
293}
294
295void BaseControllerInterface::publish_predicates() {
296 if (predicate_publisher_ == nullptr) {
297 RCLCPP_ERROR_STREAM_THROTTLE(
298 get_node()->get_logger(), *get_node()->get_clock(), 1000,
299 "No predicate publisher configured. Make sure to add predicates `on_init` of the controller.");
300 return;
301 }
302 auto message(predicate_message_);
303 for (auto predicate_it = predicates_.begin(); predicate_it != predicates_.end(); ++predicate_it) {
304 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
305 message.predicates.push_back(get_predicate_message(predicate_it->first, *new_predicate));
306 }
307 }
308 if (message.predicates.size()) {
309 predicate_publisher_->publish(message);
310 }
311}
312
313std::string BaseControllerInterface::validate_and_declare_signal(
314 const std::string& signal_name, const std::string& type, const std::string& default_topic, bool fixed_topic) {
315 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
316 if (parsed_signal_name.empty()) {
317 RCLCPP_WARN(
318 get_node()->get_logger(),
319 "The parsed signal name for %s '%s' is empty. Provide a string with valid characters for the signal name "
320 "([a-zA-Z0-9_]).",
321 type.c_str(), signal_name.c_str());
322 return "";
323 }
324 if (signal_name != parsed_signal_name) {
325 RCLCPP_WARN(
326 get_node()->get_logger(),
327 "The parsed signal name for %s '%s' is '%s'. Use the parsed signal name to refer to this %s and its topic "
328 "parameter.",
329 type.c_str(), signal_name.c_str(), parsed_signal_name.c_str(), type.c_str());
330 }
331 if (inputs_.find(parsed_signal_name) != inputs_.end()) {
332 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as input.", parsed_signal_name.c_str());
333 return "";
334 }
335 if (outputs_.find(parsed_signal_name) != outputs_.end()) {
336 RCLCPP_WARN(get_node()->get_logger(), "Signal '%s' already exists as output", parsed_signal_name.c_str());
337 return "";
338 }
339 auto topic = default_topic.empty() ? "~/" + parsed_signal_name : default_topic;
340 auto parameter_name = parsed_signal_name + "_topic";
341 if (get_node()->has_parameter(parameter_name) && get_parameter(parameter_name)->is_empty()) {
342 set_parameter_value<std::string>(parameter_name, topic);
343 } else {
345 parameter_name, topic, "Signal topic name of " + type + " '" + parsed_signal_name + "'", fixed_topic);
346 }
347 RCLCPP_DEBUG(
348 get_node()->get_logger(), "Declared %s '%s' and parameter '%s' with value '%s'.", type.c_str(),
349 parsed_signal_name.c_str(), parameter_name.c_str(), topic.c_str());
350 return parsed_signal_name;
351}
352
353void BaseControllerInterface::create_input(
354 const ControllerInput& input, const std::string& name, const std::string& topic_name) {
355 auto parsed_name = validate_and_declare_signal(name, "input", topic_name);
356 if (!parsed_name.empty()) {
357 inputs_.insert_or_assign(parsed_name, input);
358 }
359}
360
361void BaseControllerInterface::add_inputs() {
362 for (auto& [name, input] : inputs_) {
363 try {
364 auto topic = get_parameter_value<std::string>(name + "_topic");
365 std::visit(
366 overloaded{
367 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<EncodedState>>&) {
368 subscriptions_.push_back(create_subscription<EncodedState>(name, topic));
369 },
370 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Bool>>&) {
371 subscriptions_.push_back(create_subscription<std_msgs::msg::Bool>(name, topic));
372 },
373 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>>&) {
374 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64>(name, topic));
375 },
376 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64MultiArray>>&) {
377 subscriptions_.push_back(create_subscription<std_msgs::msg::Float64MultiArray>(name, topic));
378 },
379 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Int32>>&) {
380 subscriptions_.push_back(create_subscription<std_msgs::msg::Int32>(name, topic));
381 },
382 [&](const realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::String>>&) {
383 subscriptions_.push_back(create_subscription<std_msgs::msg::String>(name, topic));
384 },
385 [&](const std::any&) {
386 custom_input_configuration_callables_.at(name)(name, topic);
387 }},
388 input.buffer);
389 } catch (const std::exception& ex) {
390 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add input '%s': %s", name.c_str(), ex.what());
391 }
392 }
393}
394
395void BaseControllerInterface::create_output(
396 const PublisherVariant& publishers, const std::string& name, const std::string& topic_name) {
397 auto parsed_name = validate_and_declare_signal(name, "output", topic_name);
398 if (!parsed_name.empty()) {
399 outputs_.insert_or_assign(parsed_name, publishers);
400 }
401}
402
403void BaseControllerInterface::add_outputs() {
404 for (auto& [name, publishers] : outputs_) {
405 try {
406 auto topic = get_parameter_value<std::string>(name + "_topic");
407 std::visit(
408 overloaded{
409 [&](EncodedStatePublishers& pub) {
410 std::get<1>(pub) = get_node()->create_publisher<EncodedState>(topic, qos_);
411 std::get<2>(pub) = std::make_shared<realtime_tools::RealtimePublisher<EncodedState>>(std::get<1>(pub));
412 },
413 [&](BoolPublishers& pub) {
414 pub.first = get_node()->create_publisher<std_msgs::msg::Bool>(topic, qos_);
415 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>(pub.first);
416 },
417 [&](DoublePublishers& pub) {
418 pub.first = get_node()->create_publisher<std_msgs::msg::Float64>(topic, qos_);
419 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64>>(pub.first);
420 },
421 [&](DoubleVecPublishers& pub) {
422 pub.first = get_node()->create_publisher<std_msgs::msg::Float64MultiArray>(topic, qos_);
423 pub.second =
424 std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Float64MultiArray>>(pub.first);
425 },
426 [&](IntPublishers& pub) {
427 pub.first = get_node()->create_publisher<std_msgs::msg::Int32>(topic, qos_);
428 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Int32>>(pub.first);
429 },
430 [&](StringPublishers& pub) {
431 pub.first = get_node()->create_publisher<std_msgs::msg::String>(topic, qos_);
432 pub.second = std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::String>>(pub.first);
433 },
434 [&](CustomPublishers& pub) {
435 custom_output_configuration_callables_.at(name)(pub, name);
436 }},
437 publishers);
438 } catch (const std::bad_any_cast& ex) {
439 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add custom output '%s': %s", name.c_str(), ex.what());
440 } catch (const std::exception& ex) {
441 RCLCPP_ERROR(get_node()->get_logger(), "Failed to add output '%s': %s", name.c_str(), ex.what());
442 }
443 }
444}
445
446bool BaseControllerInterface::check_input_valid(const std::string& name) const {
447 if (inputs_.find(name) == inputs_.end()) {
448 RCLCPP_WARN_THROTTLE(
449 get_node()->get_logger(), *get_node()->get_clock(), 1000, "Could not find input '%s'", name.c_str());
450 return false;
451 }
452 if (static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(
453 std::chrono::steady_clock::now() - inputs_.at(name).timestamp)
454 .count())
455 / 1e9
456 >= input_validity_period_) {
457 return false;
458 }
459 return true;
460}
461
462std::string
463BaseControllerInterface::validate_service_name(const std::string& service_name, const std::string& type) const {
464 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
465 if (parsed_service_name.empty()) {
466 RCLCPP_WARN(
467 get_node()->get_logger(),
468 "The parsed service name for %s service '%s' is empty. Provide a string with valid characters for the service "
469 "name "
470 "([a-zA-Z0-9_]).",
471 type.c_str(), service_name.c_str());
472 return "";
473 }
474 if (service_name != parsed_service_name) {
475 RCLCPP_WARN(
476 get_node()->get_logger(),
477 "The parsed name for '%s' service '%s' is '%s'. Use the parsed name to refer to this service.", type.c_str(),
478 service_name.c_str(), parsed_service_name.c_str());
479 }
480 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
481 RCLCPP_WARN(
482 get_node()->get_logger(), "Service with name '%s' already exists as empty service.",
483 parsed_service_name.c_str());
484 return "";
485 }
486 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
487 RCLCPP_WARN(
488 get_node()->get_logger(), "Service with name '%s' already exists as string service.",
489 parsed_service_name.c_str());
490 return "";
491 }
492 RCLCPP_DEBUG(get_node()->get_logger(), "Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
493 return parsed_service_name;
494}
495
497 const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback) {
498 create_service<true>(service_name, callback);
499}
500
502 const std::string& service_name,
503 const std::function<ControllerServiceResponse(const std::string& string)>& callback) {
504 create_service<true>(service_name, callback);
505}
506
508 const std::string& service_name, const std::function<ControllerServiceResponse(void)>& callback) {
509 create_service<false>(service_name, callback);
510}
511
513 const std::string& service_name,
514 const std::function<ControllerServiceResponse(const std::string& string)>& callback) {
515 create_service<false>(service_name, callback);
516}
517
519 if (tf_buffer_ == nullptr || tf_listener_ == nullptr) {
520 RCLCPP_DEBUG(get_node()->get_logger(), "Adding TF buffer and listener.");
521 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
522 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_node()->get_clock());
523 tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, get_node());
524 } else {
525 RCLCPP_DEBUG(get_node()->get_logger(), "TF buffer and listener already exist.");
526 }
527}
528
529state_representation::CartesianPose BaseControllerInterface::lookup_transform(
530 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
531 const tf2::Duration& duration) {
532 auto transform = lookup_ros_transform(frame, reference_frame, time_point, duration);
533 state_representation::CartesianPose result(frame, reference_frame);
534 translators::read_message(result, transform);
535 return result;
536}
537
538state_representation::CartesianPose BaseControllerInterface::lookup_transform(
539 const std::string& frame, const std::string& reference_frame, double validity_period,
540 const tf2::Duration& duration) {
541 auto transform =
542 lookup_ros_transform(frame, reference_frame, tf2::TimePoint(std::chrono::microseconds(0)), duration);
543 if (validity_period > 0.0
544 && (get_node()->get_clock()->now() - transform.header.stamp).seconds() > validity_period) {
545 throw modulo_core::exceptions::LookupTransformException("Failed to lookup transform: Latest transform is too old!");
546 }
547 state_representation::CartesianPose result(frame, reference_frame);
548 translators::read_message(result, transform);
549 return result;
550}
551
552geometry_msgs::msg::TransformStamped BaseControllerInterface::lookup_ros_transform(
553 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
554 const tf2::Duration& duration) {
555 if (tf_buffer_ == nullptr || tf_listener_ == nullptr) {
557 "Failed to lookup transform: No TF buffer / listener configured.");
558 }
559 try {
560 return tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration);
561 } catch (const tf2::TransformException& ex) {
563 std::string("Failed to lookup transform: ").append(ex.what()));
564 }
565}
566
568 if (tf_broadcaster_ == nullptr) {
569 RCLCPP_DEBUG(get_node()->get_logger(), "Adding TF broadcaster.");
570 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
571 tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(get_node());
572 } else {
573 RCLCPP_DEBUG(get_node()->get_logger(), "TF broadcaster already exists.");
574 }
575}
576
578 if (static_tf_broadcaster_ == nullptr) {
579 RCLCPP_DEBUG(get_node()->get_logger(), "Adding static TF broadcaster.");
580 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
581 static_tf_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(get_node());
582 } else {
583 RCLCPP_DEBUG(get_node()->get_logger(), "Static TF broadcaster already exists.");
584 }
585}
586
587void BaseControllerInterface::send_transform(const state_representation::CartesianPose& transform) {
588 send_transforms(std::vector<state_representation::CartesianPose>{transform});
589}
590
591void BaseControllerInterface::send_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
592 publish_transforms(transforms, tf_broadcaster_);
593}
594
595void BaseControllerInterface::send_static_transform(const state_representation::CartesianPose& transform) {
596 send_static_transforms(std::vector<state_representation::CartesianPose>{transform});
597}
598
600 const std::vector<state_representation::CartesianPose>& transforms) {
601 publish_transforms(transforms, static_tf_broadcaster_, true);
602}
603
605 return qos_;
606}
607
608void BaseControllerInterface::set_qos(const rclcpp::QoS& qos) {
609 qos_ = qos;
610}
611
613 return get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
614}
615
617 return command_mutex_;
618}
619
620}// 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 add_service_lockfree(const std::string &service_name, const std::function< ControllerServiceResponse(void)> &callback)
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.
void set_parameter_value(const std::string &name, const T &value)
Set the value of a parameter.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
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.
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.
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.