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