Modulo 5.0.0
Loading...
Searching...
No Matches
ComponentInterface.cpp
1#include "modulo_components/ComponentInterface.hpp"
2
3#include <console_bridge/console.h>
4#include <tf2_msgs/msg/tf_message.hpp>
5
6#include <modulo_core/translators/message_readers.hpp>
7#include <modulo_core/translators/message_writers.hpp>
8
9using namespace modulo_core;
10
11namespace modulo_components {
12
14 const std::shared_ptr<rclcpp::node_interfaces::NodeInterfaces<ALL_RCLCPP_NODE_INTERFACES>>& interfaces)
15 : node_base_(interfaces->get_node_base_interface()),
16 node_clock_(interfaces->get_node_clock_interface()),
17 node_logging_(interfaces->get_node_logging_interface()),
18 node_parameters_(interfaces->get_node_parameters_interface()),
19 node_services_(interfaces->get_node_services_interface()),
20 node_timers_(interfaces->get_node_timers_interface()),
21 node_topics_(interfaces->get_node_topics_interface()) {
22 // register the parameter change callback handlers
23 this->pre_set_parameter_cb_handle_ = this->node_parameters_->add_pre_set_parameters_callback(
24 [this](std::vector<rclcpp::Parameter>& parameters) { return this->pre_set_parameters_callback(parameters); });
25 this->on_set_parameter_cb_handle_ = this->node_parameters_->add_on_set_parameters_callback(
26 [this](const std::vector<rclcpp::Parameter>& parameters) -> rcl_interfaces::msg::SetParametersResult {
27 return this->on_set_parameters_callback(parameters);
28 });
29 this->add_parameter("rate", 10.0, "The rate in Hertz for all periodic callbacks", true);
30
31 this->predicate_publisher_ = rclcpp::create_publisher<modulo_interfaces::msg::PredicateCollection>(
32 this->node_parameters_, this->node_topics_, "/predicates", this->qos_);
33 this->predicate_message_.node = this->node_base_->get_fully_qualified_name();
34 this->predicate_message_.type = modulo_interfaces::msg::PredicateCollection::COMPONENT;
35
36 this->rate_ = this->get_parameter_value<double>("rate");
37 this->period_ = 1.0 / this->rate_;
38 this->step_timer_ = rclcpp::create_wall_timer(
39 std::chrono::nanoseconds(static_cast<int64_t>(1e9 * this->period_)),
40 [this] {
41 if (this->step_mutex_.try_lock()) {
42 this->step();
43 this->step_mutex_.unlock();
44 }
45 },
46 nullptr, this->node_base_.get(), this->node_timers_.get());
47}
48
50 this->step_mutex_.lock();
51}
52
54 return this->rate_;
55}
56
57template<>
58double ComponentInterface::get_period() const {
59 return this->period_;
60}
61
62template<>
63std::chrono::nanoseconds ComponentInterface::get_period() const {
64 return std::chrono::nanoseconds(static_cast<int64_t>(1e9 * this->period_));
65}
66
67template<>
68rclcpp::Duration ComponentInterface::get_period() const {
69 return rclcpp::Duration::from_seconds(this->period_);
70}
71
73
75
77 const std::shared_ptr<state_representation::ParameterInterface>& parameter, const std::string& description,
78 bool read_only) {
79 rclcpp::Parameter ros_param;
80 try {
83 throw exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
84 }
85 if (!this->node_parameters_->has_parameter(parameter->get_name())) {
86 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding parameter '" << parameter->get_name() << "'.");
87 this->parameter_map_.set_parameter(parameter);
88 this->read_only_parameters_.insert_or_assign(parameter->get_name(), false);
89 try {
90 rcl_interfaces::msg::ParameterDescriptor descriptor;
91 descriptor.description = description;
92 descriptor.read_only = read_only;
93 // since the pre_set_parameters_callback is not called on parameter declaration, this has to be true
94 this->set_parameters_result_.successful = true;
95 this->set_parameters_result_.reason = "";
96 if (parameter->is_empty()) {
97 descriptor.dynamic_typing = true;
98 descriptor.type = translators::get_ros_parameter_type(parameter->get_parameter_type());
99 this->node_parameters_->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
100 } else {
101 this->node_parameters_->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
102 }
103 std::vector<rclcpp::Parameter> ros_parameters{this->node_parameters_->get_parameters({parameter->get_name()})};
104 this->pre_set_parameters_callback(ros_parameters);
105 auto result = this->on_set_parameters_callback(ros_parameters);
106 if (!result.successful) {
107 this->node_parameters_->undeclare_parameter(parameter->get_name());
109 }
110 this->read_only_parameters_.at(parameter->get_name()) = read_only;
111 } catch (const std::exception& ex) {
112 this->parameter_map_.remove_parameter(parameter->get_name());
113 this->read_only_parameters_.erase(parameter->get_name());
114 throw exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
115 }
116 } else {
118 this->node_logging_->get_logger(), "Parameter '" << parameter->get_name() << "' already exists.");
119 }
120}
121
122std::shared_ptr<state_representation::ParameterInterface>
123ComponentInterface::get_parameter(const std::string& name) const {
124 try {
125 return this->parameter_map_.get_parameter(name);
126 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
127 throw exceptions::ParameterException("Failed to get parameter '" + name + "': " + ex.what());
128 }
129}
130
131void ComponentInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
132 if (this->pre_set_parameter_callback_called_) {
133 this->pre_set_parameter_callback_called_ = false;
134 return;
135 }
136 rcl_interfaces::msg::SetParametersResult result;
137 result.successful = true;
138 for (auto& ros_parameter : parameters) {
139 try {
140 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
141 if (this->read_only_parameters_.at(ros_parameter.get_name())) {
143 this->node_logging_->get_logger(), "Parameter '" << ros_parameter.get_name() << "' is read only.");
144 continue;
145 }
146
147 // convert the ROS parameter into a ParameterInterface without modifying the original
149 if (!this->validate_parameter(new_parameter)) {
150 result.successful = false;
151 result.reason += "Validation of parameter '" + ros_parameter.get_name() + "' returned false!";
152 } else if (!new_parameter->is_empty()) {
153 // update the value of the parameter in the map
156 }
157 } catch (const std::exception& ex) {
158 result.successful = false;
159 result.reason += ex.what();
160 }
161 }
162 this->set_parameters_result_ = result;
163}
164
165rcl_interfaces::msg::SetParametersResult
166ComponentInterface::on_set_parameters_callback(const std::vector<rclcpp::Parameter>&) {
167 auto result = this->set_parameters_result_;
168 this->set_parameters_result_.successful = true;
169 this->set_parameters_result_.reason = "";
170 return result;
171}
172
173bool ComponentInterface::validate_parameter(
174 const std::shared_ptr<state_representation::ParameterInterface>& parameter) {
175 if (parameter->get_name() == "rate") {
176 auto value = parameter->get_parameter_value<double>();
177 if (value <= 0 || !std::isfinite(value)) {
178 RCLCPP_ERROR(this->node_logging_->get_logger(), "Value for parameter 'rate' has to be a positive finite number.");
179 return false;
180 }
181 }
182 return this->on_validate_parameter_callback(parameter);
183}
184
186 const std::shared_ptr<state_representation::ParameterInterface>&) {
187 return true;
188}
189
190void ComponentInterface::add_predicate(const std::string& predicate_name, bool predicate_value) {
191 this->add_predicate(predicate_name, [predicate_value]() { return predicate_value; });
192}
193
195 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
196 if (predicate_name.empty()) {
197 RCLCPP_ERROR(this->node_logging_->get_logger(), "Failed to add predicate: Provide a non empty string as a name.");
198 return;
199 }
200 if (this->predicates_.find(predicate_name) != this->predicates_.end()) {
202 this->node_logging_->get_logger(),
203 "Predicate with name '" << predicate_name << "' already exists, overwriting.");
204 } else {
205 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding predicate '" << predicate_name << "'.");
206 }
207 try {
208 this->predicates_.insert_or_assign(predicate_name, Predicate(predicate_function));
209 } catch (const std::exception& ex) {
211 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
212 "Failed to add predicate '" << predicate_name << "': " << ex.what());
213 }
214}
215
216bool ComponentInterface::get_predicate(const std::string& predicate_name) const {
217 auto predicate_it = this->predicates_.find(predicate_name);
218 if (predicate_it == this->predicates_.end()) {
220 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
221 "Failed to get predicate '" << predicate_name << "': Predicate does not exist, returning false.");
222 return false;
223 }
224 try {
225 return predicate_it->second.get_value();
226 } catch (const std::exception& ex) {
228 this->node_logging_->get_logger(),
229 "Failed to evaluate callback of predicate '" << predicate_it->first << "', returning false: " << ex.what());
230 }
231 return false;
232}
233
234void ComponentInterface::set_predicate(const std::string& predicate_name, bool predicate_value) {
235 this->set_predicate(predicate_name, [predicate_value]() { return predicate_value; });
236}
237
239 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
240 auto predicate_it = this->predicates_.find(predicate_name);
241 if (predicate_it == this->predicates_.end()) {
243 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
244 "Failed to set predicate '" << predicate_name << "': Predicate does not exist.");
245 return;
246 }
247 predicate_it->second.set_predicate(predicate_function);
248 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
249 this->publish_predicate(predicate_name, *new_predicate);
250 }
251}
252
253void ComponentInterface::add_trigger(const std::string& trigger_name) {
254 if (trigger_name.empty()) {
255 RCLCPP_ERROR(this->node_logging_->get_logger(), "Failed to add trigger: Provide a non empty string as a name.");
256 return;
257 }
258 if (std::find(this->triggers_.cbegin(), this->triggers_.cend(), trigger_name) != this->triggers_.cend()) {
260 this->node_logging_->get_logger(),
261 "Failed to add trigger: there is already a trigger with name '" << trigger_name << "'.");
262 return;
263 }
264 if (this->predicates_.find(trigger_name) != this->predicates_.end()) {
266 this->node_logging_->get_logger(),
267 "Failed to add trigger: there is already a predicate with name '" << trigger_name << "'.");
268 return;
269 }
270 this->triggers_.push_back(trigger_name);
271 this->add_predicate(trigger_name, false);
272}
273
274void ComponentInterface::trigger(const std::string& trigger_name) {
275 if (std::find(this->triggers_.cbegin(), this->triggers_.cend(), trigger_name) == this->triggers_.cend()) {
277 this->node_logging_->get_logger(),
278 "Failed to trigger: could not find trigger with name '" << trigger_name << "'.");
279 return;
280 }
281 this->set_predicate(trigger_name, true);
282 // reset the trigger to be published on the next step
283 this->predicates_.at(trigger_name).set_predicate([]() { return false; });
284}
285
287 const std::string& signal_name, const std::string& default_topic, bool fixed_topic) {
288 this->declare_signal(signal_name, "input", default_topic, fixed_topic);
289}
290
292 const std::string& signal_name, const std::string& default_topic, bool fixed_topic) {
293 this->declare_signal(signal_name, "output", default_topic, fixed_topic);
294}
295
296void ComponentInterface::declare_signal(
297 const std::string& signal_name, const std::string& type, const std::string& default_topic, bool fixed_topic) {
298 std::string parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
299 if (parsed_signal_name.empty()) {
300 throw exceptions::AddSignalException(modulo_utils::parsing::topic_validation_warning(signal_name, type));
301 }
304 this->node_logging_->get_logger(),
305 "The parsed name for " + type + " '" + signal_name + "' is '" + parsed_signal_name
306 + "'. Use the parsed name to refer to this " + type);
307 }
308 if (this->inputs_.find(parsed_signal_name) != this->inputs_.cend()) {
309 throw exceptions::AddSignalException("Signal with name '" + parsed_signal_name + "' already exists as input.");
310 }
311 if (this->outputs_.find(parsed_signal_name) != this->outputs_.cend()) {
312 throw exceptions::AddSignalException("Signal with name '" + parsed_signal_name + "' already exists as output.");
313 }
314 std::string topic_name = default_topic.empty() ? "~/" + parsed_signal_name : default_topic;
315 auto parameter_name = parsed_signal_name + "_topic";
316 if (this->node_parameters_->has_parameter(parameter_name) && this->get_parameter(parameter_name)->is_empty()) {
318 } else {
319 this->add_parameter(
320 parameter_name, topic_name, "Signal topic name of " + type + " '" + parsed_signal_name + "'", fixed_topic);
321 }
323 this->node_logging_->get_logger(),
324 "Declared signal '" << parsed_signal_name << "' and parameter '" << parameter_name << "' with value '"
325 << topic_name << "'.");
326}
327
328void ComponentInterface::publish_output(const std::string& signal_name) {
329 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
330 if (this->outputs_.find(parsed_signal_name) == this->outputs_.cend()) {
331 throw exceptions::CoreException("Output with name '" + signal_name + "' doesn't exist.");
332 }
333 if (this->periodic_outputs_.at(parsed_signal_name)) {
334 throw exceptions::CoreException("An output that is published periodically cannot be triggered manually.");
335 }
336 try {
337 this->outputs_.at(parsed_signal_name)->publish();
338 } catch (const exceptions::CoreException& ex) {
340 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
341 "Failed to publish output '" << parsed_signal_name << "': " << ex.what());
342 }
343}
344
345void ComponentInterface::remove_input(const std::string& signal_name) {
346 if (!this->remove_signal(signal_name, this->inputs_)) {
347 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
348 if (!this->remove_signal(parsed_signal_name, this->inputs_)) {
350 this->node_logging_->get_logger(),
351 "Unknown input '" << signal_name << "' (parsed name was '" << parsed_signal_name << "').");
352 }
353 }
354}
355
356void ComponentInterface::remove_output(const std::string& signal_name) {
357 if (!this->remove_signal(signal_name, this->outputs_)) {
358 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
359 if (!this->remove_signal(parsed_signal_name, this->outputs_)) {
361 this->node_logging_->get_logger(),
362 "Unknown output '" << signal_name << "' (parsed name was '" << parsed_signal_name << "').");
363 }
364 }
365}
366
368 const std::string& service_name, const std::function<ComponentServiceResponse(void)>& callback) {
369 try {
370 std::string parsed_service_name = this->validate_service_name(service_name, "empty");
371 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding empty service '" << parsed_service_name << "'.");
372 auto service = rclcpp::create_service<modulo_interfaces::srv::EmptyTrigger>(
373 this->node_base_, this->node_services_, "~/" + parsed_service_name,
374 [callback](
375 const std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Request>,
376 std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Response> response) {
377 try {
379 response->success = callback_response.success;
380 response->message = callback_response.message;
381 } catch (const std::exception& ex) {
382 response->success = false;
383 response->message = ex.what();
384 }
385 },
386 this->qos_, nullptr);
387 this->empty_services_.insert_or_assign(parsed_service_name, service);
388 } catch (const std::exception& ex) {
390 this->node_logging_->get_logger(), "Failed to add service '" << service_name << "': " << ex.what());
391 }
392}
393
395 const std::string& service_name,
396 const std::function<ComponentServiceResponse(const std::string& string)>& callback) {
397 try {
398 std::string parsed_service_name = this->validate_service_name(service_name, "string");
399 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding string service '" << parsed_service_name << "'.");
400 auto service = rclcpp::create_service<modulo_interfaces::srv::StringTrigger>(
401 this->node_base_, this->node_services_, "~/" + parsed_service_name,
402 [callback](
403 const std::shared_ptr<modulo_interfaces::srv::StringTrigger::Request> request,
404 std::shared_ptr<modulo_interfaces::srv::StringTrigger::Response> response) {
405 try {
406 auto callback_response = callback(request->payload);
407 response->success = callback_response.success;
408 response->message = callback_response.message;
409 } catch (const std::exception& ex) {
410 response->success = false;
411 response->message = ex.what();
412 }
413 },
414 this->qos_, nullptr);
415 this->string_services_.insert_or_assign(parsed_service_name, service);
416 } catch (const std::exception& ex) {
418 this->node_logging_->get_logger(), "Failed to add service '" << service_name << "': " << ex.what());
419 }
420}
421
422// FIXME: use enum for service type
423std::string ComponentInterface::validate_service_name(const std::string& service_name, const std::string& type) const {
424 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
425 if (parsed_service_name.empty()) {
427 modulo_utils::parsing::topic_validation_warning(service_name, type + " service"));
428 }
431 this->node_logging_->get_logger(),
432 "The parsed name for service '" + service_name + "' is '" + parsed_service_name
433 + "'. Use the parsed name to refer to this service");
434 }
435 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
437 "Service with name '" + parsed_service_name + "' already exists as an empty service.");
438 }
439 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
441 "Service with name '" + parsed_service_name + "' already exists as a string service.");
442 }
443 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
444 return parsed_service_name;
445}
446
447void ComponentInterface::add_periodic_callback(const std::string& name, const std::function<void()>& callback) {
448 if (name.empty()) {
450 this->node_logging_->get_logger(), "Failed to add periodic function: Provide a non empty string as a name.");
451 return;
452 }
453 if (this->periodic_callbacks_.find(name) != this->periodic_callbacks_.end()) {
455 this->node_logging_->get_logger(), "Periodic function '" << name << "' already exists, overwriting.");
456 } else {
457 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding periodic function '" << name << "'.");
458 }
459 this->periodic_callbacks_.insert_or_assign(name, callback);
460}
461
463 if (this->tf_broadcaster_ == nullptr) {
464 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding TF broadcaster.");
465 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
466 this->tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(
467 this->node_parameters_, this->node_topics_, tf2_ros::DynamicBroadcasterQoS());
468 } else {
469 RCLCPP_DEBUG(this->node_logging_->get_logger(), "TF broadcaster already exists.");
470 }
471}
472
474 if (this->static_tf_broadcaster_ == nullptr) {
475 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding static TF broadcaster.");
476 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
477 tf2_ros::StaticBroadcasterQoS qos;
478 rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
479 this->static_tf_broadcaster_ =
480 std::make_shared<tf2_ros::StaticTransformBroadcaster>(this->node_parameters_, this->node_topics_, qos, options);
481 } else {
482 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Static TF broadcaster already exists.");
483 }
484}
485
487 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
488 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding TF buffer and listener.");
489 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
490 this->tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->node_clock_->get_clock());
491 this->tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*this->tf_buffer_);
492 } else {
493 RCLCPP_DEBUG(this->node_logging_->get_logger(), "TF buffer and listener already exist.");
494 }
495}
496
497void ComponentInterface::send_transform(const state_representation::CartesianPose& transform) {
498 this->send_transforms(std::vector<state_representation::CartesianPose>{transform});
499}
500
501void ComponentInterface::send_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
502 this->publish_transforms(transforms, this->tf_broadcaster_);
503}
504
505void ComponentInterface::send_static_transform(const state_representation::CartesianPose& transform) {
506 this->send_static_transforms(std::vector<state_representation::CartesianPose>{transform});
507}
508
509void ComponentInterface::send_static_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
510 this->publish_transforms(transforms, this->static_tf_broadcaster_, true);
511}
512
513state_representation::CartesianPose ComponentInterface::lookup_transform(
514 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
515 const tf2::Duration& duration) {
516 auto transform = this->lookup_ros_transform(frame, reference_frame, time_point, duration);
517 state_representation::CartesianPose result(frame, reference_frame);
519 return result;
520}
521
522state_representation::CartesianPose ComponentInterface::lookup_transform(
523 const std::string& frame, const std::string& reference_frame, double validity_period,
524 const tf2::Duration& duration) {
525 auto transform =
526 this->lookup_ros_transform(frame, reference_frame, tf2::TimePoint(std::chrono::microseconds(0)), duration);
527 if (validity_period > 0.0
528 && (this->node_clock_->get_clock()->now() - transform.header.stamp).seconds() > validity_period) {
529 throw exceptions::LookupTransformException("Failed to lookup transform: Latest transform is too old!");
530 }
531 state_representation::CartesianPose result(frame, reference_frame);
533 return result;
534}
535
536geometry_msgs::msg::TransformStamped ComponentInterface::lookup_ros_transform(
537 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
538 const tf2::Duration& duration) {
539 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
540 throw exceptions::LookupTransformException("Failed to lookup transform: To TF buffer / listener configured.");
541 }
542 try {
543 return this->tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration);
544 } catch (const tf2::TransformException& ex) {
545 throw exceptions::LookupTransformException(std::string("Failed to lookup transform: ").append(ex.what()));
546 }
547}
548
549rclcpp::QoS ComponentInterface::get_qos() const {
550 return this->qos_;
551}
552
553void ComponentInterface::set_qos(const rclcpp::QoS& qos) {
554 this->qos_ = qos;
555}
556
558 RCLCPP_ERROR(this->node_logging_->get_logger(), "An error was raised in the component.");
559}
560
561modulo_interfaces::msg::Predicate ComponentInterface::get_predicate_message(const std::string& name, bool value) const {
562 modulo_interfaces::msg::Predicate message;
563 message.predicate = name;
564 message.value = value;
565 return message;
566}
567
568void ComponentInterface::publish_predicate(const std::string& name, bool value) const {
569 auto message(this->predicate_message_);
570 message.predicates.push_back(this->get_predicate_message(name, value));
571 this->predicate_publisher_->publish(message);
572}
573
575 auto message(this->predicate_message_);
576 for (auto predicate_it = this->predicates_.begin(); predicate_it != this->predicates_.end(); ++predicate_it) {
577 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
578 message.predicates.push_back(this->get_predicate_message(predicate_it->first, *new_predicate));
579 }
580 }
581 if (message.predicates.size()) {
582 this->predicate_publisher_->publish(message);
583 }
584}
585
587 for (const auto& [signal, publisher] : this->outputs_) {
588 try {
589 if (this->periodic_outputs_.at(signal)) {
590 publisher->publish();
591 }
592 } catch (const exceptions::CoreException& ex) {
594 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
595 "Failed to publish output '" << signal << "': " << ex.what());
596 }
597 }
598}
599
601 for (const auto& [name, callback] : this->periodic_callbacks_) {
602 try {
603 callback();
604 } catch (const std::exception& ex) {
606 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
607 "Failed to evaluate periodic function callback '" << name << "': " << ex.what());
608 }
609 }
610}
611
613 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Finalizing all interfaces.");
614 this->inputs_.clear();
615 this->outputs_.clear();
616 this->predicate_publisher_.reset();
617 this->empty_services_.clear();
618 this->string_services_.clear();
619 if (this->step_timer_ != nullptr) {
620 this->step_timer_->cancel();
621 }
622 this->step_timer_.reset();
623 this->tf_buffer_.reset();
624 this->tf_listener_.reset();
625 this->tf_broadcaster_.reset();
626 this->static_tf_broadcaster_.reset();
627}
628}// namespace modulo_components
double get_rate() const
Get the component rate in Hertz.
void send_transforms(const std::vector< state_representation::CartesianPose > &transforms)
Send a vector of transforms to TF.
virtual bool on_validate_parameter_callback(const std::shared_ptr< state_representation::ParameterInterface > &parameter)
Parameter validation function to be redefined by derived Component classes.
void publish_outputs()
Helper function to publish all output signals.
void remove_input(const std::string &signal_name)
Remove an input from the map of inputs.
void declare_input(const std::string &signal_name, const std::string &default_topic="", bool fixed_topic=false)
Declare an input to create the topic parameter without adding it to the map of inputs yet.
void declare_output(const std::string &signal_name, const std::string &default_topic="", bool fixed_topic=false)
Declare an output to create the topic parameter without adding it to the map of outputs yet.
T get_period() const
Get the component period.
void send_static_transforms(const std::vector< state_representation::CartesianPose > &transforms)
Send a vector of static transforms to TF.
std::map< std::string, std::shared_ptr< modulo_core::communication::PublisherInterface > > outputs_
Map of outputs.
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
void finalize_interfaces()
Finalize all interfaces.
T get_parameter_value(const std::string &name) const
Get a parameter value by name.
virtual ~ComponentInterface()
Virtual destructor.
void add_static_tf_broadcaster()
Configure a static transform broadcaster.
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.
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.
virtual void on_step_callback()
Steps to execute periodically. To be redefined by derived Component classes.
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...
virtual void raise_error()
Notify an error in the component.
ComponentInterface(const std::shared_ptr< rclcpp::node_interfaces::NodeInterfaces< ALL_RCLCPP_NODE_INTERFACES > > &interfaces)
Constructor with all node interfaces.
void remove_output(const std::string &signal_name)
Remove an output from the map of outputs.
void publish_output(const std::string &signal_name)
Trigger the publishing of an output.
virtual void step()
Step function that is called periodically.
void publish_predicates()
Helper function to publish all predicates.
void set_qos(const rclcpp::QoS &qos)
Set the Quality of Service for ROS publishers and subscribers.
rclcpp::QoS get_qos() const
Getter of the Quality of Service attribute.
void add_predicate(const std::string &predicate_name, bool predicate_value)
Add a predicate to the map of predicates.
void send_transform(const state_representation::CartesianPose &transform)
Send a transform to TF.
void add_trigger(const std::string &trigger_name)
Add a trigger to the component. Triggers are predicates that are always false except when it's trigge...
void add_periodic_callback(const std::string &name, const std::function< void(void)> &callback)
Add a periodic callback function.
std::map< std::string, std::shared_ptr< modulo_core::communication::SubscriptionInterface > > inputs_
Map of inputs.
void add_tf_listener()
Configure a transform buffer and listener.
void evaluate_periodic_callbacks()
Helper function to evaluate all periodic function callbacks.
void add_tf_broadcaster()
Configure a transform broadcaster.
void send_static_transform(const state_representation::CartesianPose &transform)
Send a static transform to TF.
bool get_predicate(const std::string &predicate_name) const
Get the logical value of a predicate.
std::map< std::string, bool > periodic_outputs_
Map of outputs with periodic publishing flag.
void add_service(const std::string &service_name, const std::function< ComponentServiceResponse(void)> &callback)
Add a service to trigger a callback function with no input arguments.
An exception class to notify errors when adding a service.
An exception class to notify errors when adding a signal.
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.
Modulo components.
Definition Component.hpp:9
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 component services.