Modulo 4.2.2
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->add_predicate("in_error_state", false);
37
38 this->rate_ = this->get_parameter_value<double>("rate");
39 this->period_ = 1.0 / this->rate_;
40 this->step_timer_ = rclcpp::create_wall_timer(
41 std::chrono::nanoseconds(static_cast<int64_t>(1e9 * this->period_)),
42 [this] {
43 if (this->step_mutex_.try_lock()) {
44 this->step();
45 this->step_mutex_.unlock();
46 }
47 },
48 nullptr, this->node_base_.get(), this->node_timers_.get());
49}
50
52 this->step_mutex_.lock();
53}
54
56 return this->rate_;
57}
58
59template<>
60double ComponentInterface::get_period() const {
61 return this->period_;
62}
63
64template<>
65std::chrono::nanoseconds ComponentInterface::get_period() const {
66 return std::chrono::nanoseconds(static_cast<int64_t>(1e9 * this->period_));
67}
68
69template<>
70rclcpp::Duration ComponentInterface::get_period() const {
71 return rclcpp::Duration::from_seconds(this->period_);
72}
73
75
77
79 const std::shared_ptr<state_representation::ParameterInterface>& parameter, const std::string& description,
80 bool read_only) {
81 rclcpp::Parameter ros_param;
82 try {
85 throw exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
86 }
87 if (!this->node_parameters_->has_parameter(parameter->get_name())) {
88 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding parameter '" << parameter->get_name() << "'.");
89 this->parameter_map_.set_parameter(parameter);
90 this->read_only_parameters_.insert_or_assign(parameter->get_name(), false);
91 try {
92 rcl_interfaces::msg::ParameterDescriptor descriptor;
93 descriptor.description = description;
94 descriptor.read_only = read_only;
95 // since the pre_set_parameters_callback is not called on parameter declaration, this has to be true
96 this->set_parameters_result_.successful = true;
97 this->set_parameters_result_.reason = "";
98 if (parameter->is_empty()) {
99 descriptor.dynamic_typing = true;
100 descriptor.type = translators::get_ros_parameter_type(parameter->get_parameter_type());
101 this->node_parameters_->declare_parameter(parameter->get_name(), rclcpp::ParameterValue{}, descriptor);
102 } else {
103 this->node_parameters_->declare_parameter(parameter->get_name(), ros_param.get_parameter_value(), descriptor);
104 }
105 std::vector<rclcpp::Parameter> ros_parameters{this->node_parameters_->get_parameters({parameter->get_name()})};
106 this->pre_set_parameters_callback(ros_parameters);
107 auto result = this->on_set_parameters_callback(ros_parameters);
108 if (!result.successful) {
109 this->node_parameters_->undeclare_parameter(parameter->get_name());
111 }
112 this->read_only_parameters_.at(parameter->get_name()) = read_only;
113 } catch (const std::exception& ex) {
114 this->parameter_map_.remove_parameter(parameter->get_name());
115 this->read_only_parameters_.erase(parameter->get_name());
116 throw exceptions::ParameterException("Failed to add parameter: " + std::string(ex.what()));
117 }
118 } else {
120 this->node_logging_->get_logger(), "Parameter '" << parameter->get_name() << "' already exists.");
121 }
122}
123
124std::shared_ptr<state_representation::ParameterInterface>
125ComponentInterface::get_parameter(const std::string& name) const {
126 try {
127 return this->parameter_map_.get_parameter(name);
128 } catch (const state_representation::exceptions::InvalidParameterException& ex) {
129 throw exceptions::ParameterException("Failed to get parameter '" + name + "': " + ex.what());
130 }
131}
132
133void ComponentInterface::pre_set_parameters_callback(std::vector<rclcpp::Parameter>& parameters) {
134 if (this->pre_set_parameter_callback_called_) {
135 this->pre_set_parameter_callback_called_ = false;
136 return;
137 }
138 rcl_interfaces::msg::SetParametersResult result;
139 result.successful = true;
140 for (auto& ros_parameter : parameters) {
141 try {
142 auto parameter = parameter_map_.get_parameter(ros_parameter.get_name());
143 if (this->read_only_parameters_.at(ros_parameter.get_name())) {
145 this->node_logging_->get_logger(), "Parameter '" << ros_parameter.get_name() << "' is read only.");
146 continue;
147 }
148
149 // convert the ROS parameter into a ParameterInterface without modifying the original
151 if (!this->validate_parameter(new_parameter)) {
152 result.successful = false;
153 result.reason += "Validation of parameter '" + ros_parameter.get_name() + "' returned false!";
154 } else if (!new_parameter->is_empty()) {
155 // update the value of the parameter in the map
158 }
159 } catch (const std::exception& ex) {
160 result.successful = false;
161 result.reason += ex.what();
162 }
163 }
164 this->set_parameters_result_ = result;
165}
166
167rcl_interfaces::msg::SetParametersResult
168ComponentInterface::on_set_parameters_callback(const std::vector<rclcpp::Parameter>&) {
169 auto result = this->set_parameters_result_;
170 this->set_parameters_result_.successful = true;
171 this->set_parameters_result_.reason = "";
172 return result;
173}
174
175bool ComponentInterface::validate_parameter(
176 const std::shared_ptr<state_representation::ParameterInterface>& parameter) {
177 if (parameter->get_name() == "rate") {
178 auto value = parameter->get_parameter_value<double>();
179 if (value <= 0 || !std::isfinite(value)) {
180 RCLCPP_ERROR(this->node_logging_->get_logger(), "Value for parameter 'rate' has to be a positive finite number.");
181 return false;
182 }
183 }
184 return this->on_validate_parameter_callback(parameter);
185}
186
188 const std::shared_ptr<state_representation::ParameterInterface>&) {
189 return true;
190}
191
192void ComponentInterface::add_predicate(const std::string& predicate_name, bool predicate_value) {
193 this->add_predicate(predicate_name, [predicate_value]() { return predicate_value; });
194}
195
197 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
198 if (predicate_name.empty()) {
199 RCLCPP_ERROR(this->node_logging_->get_logger(), "Failed to add predicate: Provide a non empty string as a name.");
200 return;
201 }
202 if (this->predicates_.find(predicate_name) != this->predicates_.end()) {
204 this->node_logging_->get_logger(),
205 "Predicate with name '" << predicate_name << "' already exists, overwriting.");
206 } else {
207 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding predicate '" << predicate_name << "'.");
208 }
209 try {
210 this->predicates_.insert_or_assign(predicate_name, Predicate(predicate_function));
211 } catch (const std::exception& ex) {
213 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
214 "Failed to add predicate '" << predicate_name << "': " << ex.what());
215 }
216}
217
218bool ComponentInterface::get_predicate(const std::string& predicate_name) const {
219 auto predicate_it = this->predicates_.find(predicate_name);
220 if (predicate_it == this->predicates_.end()) {
222 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
223 "Failed to get predicate '" << predicate_name << "': Predicate does not exist, returning false.");
224 return false;
225 }
226 try {
227 return predicate_it->second.get_value();
228 } catch (const std::exception& ex) {
230 this->node_logging_->get_logger(),
231 "Failed to evaluate callback of predicate '" << predicate_it->first << "', returning false: " << ex.what());
232 }
233 return false;
234}
235
236void ComponentInterface::set_predicate(const std::string& predicate_name, bool predicate_value) {
237 this->set_predicate(predicate_name, [predicate_value]() { return predicate_value; });
238}
239
241 const std::string& predicate_name, const std::function<bool(void)>& predicate_function) {
242 auto predicate_it = this->predicates_.find(predicate_name);
243 if (predicate_it == this->predicates_.end()) {
245 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
246 "Failed to set predicate '" << predicate_name << "': Predicate does not exist.");
247 return;
248 }
249 predicate_it->second.set_predicate(predicate_function);
250 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
251 this->publish_predicate(predicate_name, *new_predicate);
252 }
253}
254
255void ComponentInterface::add_trigger(const std::string& trigger_name) {
256 if (trigger_name.empty()) {
257 RCLCPP_ERROR(this->node_logging_->get_logger(), "Failed to add trigger: Provide a non empty string as a name.");
258 return;
259 }
260 if (std::find(this->triggers_.cbegin(), this->triggers_.cend(), trigger_name) != this->triggers_.cend()) {
262 this->node_logging_->get_logger(),
263 "Failed to add trigger: there is already a trigger with name '" << trigger_name << "'.");
264 return;
265 }
266 if (this->predicates_.find(trigger_name) != this->predicates_.end()) {
268 this->node_logging_->get_logger(),
269 "Failed to add trigger: there is already a predicate with name '" << trigger_name << "'.");
270 return;
271 }
272 this->triggers_.push_back(trigger_name);
273 this->add_predicate(trigger_name, false);
274}
275
276void ComponentInterface::trigger(const std::string& trigger_name) {
277 if (std::find(this->triggers_.cbegin(), this->triggers_.cend(), trigger_name) == this->triggers_.cend()) {
279 this->node_logging_->get_logger(),
280 "Failed to trigger: could not find trigger with name '" << trigger_name << "'.");
281 return;
282 }
283 this->set_predicate(trigger_name, true);
284 // reset the trigger to be published on the next step
285 this->predicates_.at(trigger_name).set_predicate([]() { return false; });
286}
287
289 const std::string& signal_name, const std::string& default_topic, bool fixed_topic) {
290 this->declare_signal(signal_name, "input", default_topic, fixed_topic);
291}
292
294 const std::string& signal_name, const std::string& default_topic, bool fixed_topic) {
295 this->declare_signal(signal_name, "output", default_topic, fixed_topic);
296}
297
298void ComponentInterface::declare_signal(
299 const std::string& signal_name, const std::string& type, const std::string& default_topic, bool fixed_topic) {
300 std::string parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
301 if (parsed_signal_name.empty()) {
302 throw exceptions::AddSignalException(modulo_utils::parsing::topic_validation_warning(signal_name, type));
303 }
306 this->node_logging_->get_logger(),
307 "The parsed name for " + type + " '" + signal_name + "' is '" + parsed_signal_name
308 + "'. Use the parsed name to refer to this " + type);
309 }
310 if (this->inputs_.find(parsed_signal_name) != this->inputs_.cend()) {
311 throw exceptions::AddSignalException("Signal with name '" + parsed_signal_name + "' already exists as input.");
312 }
313 if (this->outputs_.find(parsed_signal_name) != this->outputs_.cend()) {
314 throw exceptions::AddSignalException("Signal with name '" + parsed_signal_name + "' already exists as output.");
315 }
316 std::string topic_name = default_topic.empty() ? "~/" + parsed_signal_name : default_topic;
317 auto parameter_name = parsed_signal_name + "_topic";
318 if (this->node_parameters_->has_parameter(parameter_name) && this->get_parameter(parameter_name)->is_empty()) {
320 } else {
321 this->add_parameter(
322 parameter_name, topic_name, "Signal topic name of " + type + " '" + parsed_signal_name + "'", fixed_topic);
323 }
325 this->node_logging_->get_logger(),
326 "Declared signal '" << parsed_signal_name << "' and parameter '" << parameter_name << "' with value '"
327 << topic_name << "'.");
328}
329
330void ComponentInterface::publish_output(const std::string& signal_name) {
331 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
332 if (this->outputs_.find(parsed_signal_name) == this->outputs_.cend()) {
333 throw exceptions::CoreException("Output with name '" + signal_name + "' doesn't exist.");
334 }
335 if (this->periodic_outputs_.at(parsed_signal_name)) {
336 throw exceptions::CoreException("An output that is published periodically cannot be triggered manually.");
337 }
338 try {
339 this->outputs_.at(parsed_signal_name)->publish();
340 } catch (const exceptions::CoreException& ex) {
342 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
343 "Failed to publish output '" << parsed_signal_name << "': " << ex.what());
344 }
345}
346
347void ComponentInterface::remove_input(const std::string& signal_name) {
348 if (!this->remove_signal(signal_name, this->inputs_)) {
349 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
350 if (!this->remove_signal(parsed_signal_name, this->inputs_)) {
352 this->node_logging_->get_logger(),
353 "Unknown input '" << signal_name << "' (parsed name was '" << parsed_signal_name << "').");
354 }
355 }
356}
357
358void ComponentInterface::remove_output(const std::string& signal_name) {
359 if (!this->remove_signal(signal_name, this->outputs_)) {
360 auto parsed_signal_name = modulo_utils::parsing::parse_topic_name(signal_name);
361 if (!this->remove_signal(parsed_signal_name, this->outputs_)) {
363 this->node_logging_->get_logger(),
364 "Unknown output '" << signal_name << "' (parsed name was '" << parsed_signal_name << "').");
365 }
366 }
367}
368
370 const std::string& service_name, const std::function<ComponentServiceResponse(void)>& callback) {
371 try {
372 std::string parsed_service_name = this->validate_service_name(service_name, "empty");
373 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding empty service '" << parsed_service_name << "'.");
374 auto service = rclcpp::create_service<modulo_interfaces::srv::EmptyTrigger>(
375 this->node_base_, this->node_services_, "~/" + parsed_service_name,
376 [callback](
377 const std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Request>,
378 std::shared_ptr<modulo_interfaces::srv::EmptyTrigger::Response> response) {
379 try {
381 response->success = callback_response.success;
382 response->message = callback_response.message;
383 } catch (const std::exception& ex) {
384 response->success = false;
385 response->message = ex.what();
386 }
387 },
388 this->qos_, nullptr);
389 this->empty_services_.insert_or_assign(parsed_service_name, service);
390 } catch (const std::exception& ex) {
392 this->node_logging_->get_logger(), "Failed to add service '" << service_name << "': " << ex.what());
393 }
394}
395
397 const std::string& service_name,
398 const std::function<ComponentServiceResponse(const std::string& string)>& callback) {
399 try {
400 std::string parsed_service_name = this->validate_service_name(service_name, "string");
401 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding string service '" << parsed_service_name << "'.");
402 auto service = rclcpp::create_service<modulo_interfaces::srv::StringTrigger>(
403 this->node_base_, this->node_services_, "~/" + parsed_service_name,
404 [callback](
405 const std::shared_ptr<modulo_interfaces::srv::StringTrigger::Request> request,
406 std::shared_ptr<modulo_interfaces::srv::StringTrigger::Response> response) {
407 try {
408 auto callback_response = callback(request->payload);
409 response->success = callback_response.success;
410 response->message = callback_response.message;
411 } catch (const std::exception& ex) {
412 response->success = false;
413 response->message = ex.what();
414 }
415 },
416 this->qos_, nullptr);
417 this->string_services_.insert_or_assign(parsed_service_name, service);
418 } catch (const std::exception& ex) {
420 this->node_logging_->get_logger(), "Failed to add service '" << service_name << "': " << ex.what());
421 }
422}
423
424// FIXME: use enum for service type
425std::string ComponentInterface::validate_service_name(const std::string& service_name, const std::string& type) const {
426 std::string parsed_service_name = modulo_utils::parsing::parse_topic_name(service_name);
427 if (parsed_service_name.empty()) {
429 modulo_utils::parsing::topic_validation_warning(service_name, type + " service"));
430 }
433 this->node_logging_->get_logger(),
434 "The parsed name for service '" + service_name + "' is '" + parsed_service_name
435 + "'. Use the parsed name to refer to this service");
436 }
437 if (empty_services_.find(parsed_service_name) != empty_services_.cend()) {
439 "Service with name '" + parsed_service_name + "' already exists as an empty service.");
440 }
441 if (string_services_.find(parsed_service_name) != string_services_.cend()) {
443 "Service with name '" + parsed_service_name + "' already exists as a string service.");
444 }
445 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding %s service '%s'.", type.c_str(), parsed_service_name.c_str());
446 return parsed_service_name;
447}
448
449void ComponentInterface::add_periodic_callback(const std::string& name, const std::function<void()>& callback) {
450 if (name.empty()) {
452 this->node_logging_->get_logger(), "Failed to add periodic function: Provide a non empty string as a name.");
453 return;
454 }
455 if (this->periodic_callbacks_.find(name) != this->periodic_callbacks_.end()) {
457 this->node_logging_->get_logger(), "Periodic function '" << name << "' already exists, overwriting.");
458 } else {
459 RCLCPP_DEBUG_STREAM(this->node_logging_->get_logger(), "Adding periodic function '" << name << "'.");
460 }
461 this->periodic_callbacks_.insert_or_assign(name, callback);
462}
463
465 if (this->tf_broadcaster_ == nullptr) {
466 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding TF broadcaster.");
467 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
468 this->tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(
469 this->node_parameters_, this->node_topics_, tf2_ros::DynamicBroadcasterQoS());
470 } else {
471 RCLCPP_DEBUG(this->node_logging_->get_logger(), "TF broadcaster already exists.");
472 }
473}
474
476 if (this->static_tf_broadcaster_ == nullptr) {
477 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding static TF broadcaster.");
478 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
479 tf2_ros::StaticBroadcasterQoS qos;
480 rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
481 this->static_tf_broadcaster_ =
482 std::make_shared<tf2_ros::StaticTransformBroadcaster>(this->node_parameters_, this->node_topics_, qos, options);
483 } else {
484 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Static TF broadcaster already exists.");
485 }
486}
487
489 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
490 RCLCPP_DEBUG(this->node_logging_->get_logger(), "Adding TF buffer and listener.");
491 console_bridge::setLogLevel(console_bridge::CONSOLE_BRIDGE_LOG_NONE);
492 this->tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->node_clock_->get_clock());
493 this->tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*this->tf_buffer_);
494 } else {
495 RCLCPP_DEBUG(this->node_logging_->get_logger(), "TF buffer and listener already exist.");
496 }
497}
498
499void ComponentInterface::send_transform(const state_representation::CartesianPose& transform) {
500 this->send_transforms(std::vector<state_representation::CartesianPose>{transform});
501}
502
503void ComponentInterface::send_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
504 this->publish_transforms(transforms, this->tf_broadcaster_);
505}
506
507void ComponentInterface::send_static_transform(const state_representation::CartesianPose& transform) {
508 this->send_static_transforms(std::vector<state_representation::CartesianPose>{transform});
509}
510
511void ComponentInterface::send_static_transforms(const std::vector<state_representation::CartesianPose>& transforms) {
512 this->publish_transforms(transforms, this->static_tf_broadcaster_, true);
513}
514
515state_representation::CartesianPose ComponentInterface::lookup_transform(
516 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
517 const tf2::Duration& duration) {
518 auto transform = this->lookup_ros_transform(frame, reference_frame, time_point, duration);
519 state_representation::CartesianPose result(frame, reference_frame);
521 return result;
522}
523
524state_representation::CartesianPose ComponentInterface::lookup_transform(
525 const std::string& frame, const std::string& reference_frame, double validity_period,
526 const tf2::Duration& duration) {
527 auto transform =
528 this->lookup_ros_transform(frame, reference_frame, tf2::TimePoint(std::chrono::microseconds(0)), duration);
529 if (validity_period > 0.0
530 && (this->node_clock_->get_clock()->now() - transform.header.stamp).seconds() > validity_period) {
531 throw exceptions::LookupTransformException("Failed to lookup transform: Latest transform is too old!");
532 }
533 state_representation::CartesianPose result(frame, reference_frame);
535 return result;
536}
537
538geometry_msgs::msg::TransformStamped ComponentInterface::lookup_ros_transform(
539 const std::string& frame, const std::string& reference_frame, const tf2::TimePoint& time_point,
540 const tf2::Duration& duration) {
541 if (this->tf_buffer_ == nullptr || this->tf_listener_ == nullptr) {
542 throw exceptions::LookupTransformException("Failed to lookup transform: To TF buffer / listener configured.");
543 }
544 try {
545 return this->tf_buffer_->lookupTransform(reference_frame, frame, time_point, duration);
546 } catch (const tf2::TransformException& ex) {
547 throw exceptions::LookupTransformException(std::string("Failed to lookup transform: ").append(ex.what()));
548 }
549}
550
551rclcpp::QoS ComponentInterface::get_qos() const {
552 return this->qos_;
553}
554
555void ComponentInterface::set_qos(const rclcpp::QoS& qos) {
556 this->qos_ = qos;
557}
558
560 RCLCPP_DEBUG(this->node_logging_->get_logger(), "raise_error called: Setting predicate 'in_error_state' to true.");
561 this->set_predicate("in_error_state", true);
562}
563
564modulo_interfaces::msg::Predicate ComponentInterface::get_predicate_message(const std::string& name, bool value) const {
565 modulo_interfaces::msg::Predicate message;
566 message.predicate = name;
567 message.value = value;
568 return message;
569}
570
571void ComponentInterface::publish_predicate(const std::string& name, bool value) const {
572 auto message(this->predicate_message_);
573 message.predicates.push_back(this->get_predicate_message(name, value));
574 this->predicate_publisher_->publish(message);
575}
576
578 auto message(this->predicate_message_);
579 for (auto predicate_it = this->predicates_.begin(); predicate_it != this->predicates_.end(); ++predicate_it) {
580 if (auto new_predicate = predicate_it->second.query(); new_predicate) {
581 message.predicates.push_back(this->get_predicate_message(predicate_it->first, *new_predicate));
582 }
583 }
584 if (message.predicates.size()) {
585 this->predicate_publisher_->publish(message);
586 }
587}
588
590 for (const auto& [signal, publisher] : this->outputs_) {
591 try {
592 if (this->periodic_outputs_.at(signal)) {
593 publisher->publish();
594 }
595 } catch (const exceptions::CoreException& ex) {
597 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
598 "Failed to publish output '" << signal << "': " << ex.what());
599 }
600 }
601}
602
604 for (const auto& [name, callback] : this->periodic_callbacks_) {
605 try {
606 callback();
607 } catch (const std::exception& ex) {
609 this->node_logging_->get_logger(), *this->node_clock_->get_clock(), 1000,
610 "Failed to evaluate periodic function callback '" << name << "': " << ex.what());
611 }
612 }
613}
614}// 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.
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()
Put the component in error state by setting the 'in_error_state' predicate to true.
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.