1#include "modulo_components/Component.hpp"
9 : Node(modulo_utils::parsing::parse_node_name(node_options, fallback_name), node_options),
10 ComponentInterface(std::make_shared<node_interfaces::NodeInterfaces<ALL_RCLCPP_NODE_INTERFACES>>(
11 Node::get_node_base_interface(), Node::get_node_clock_interface(), Node::get_node_graph_interface(),
12 Node::get_node_logging_interface(), Node::get_node_parameters_interface(),
13 Node::get_node_services_interface(), Node::get_node_time_source_interface(),
14 Node::get_node_timers_interface(), Node::get_node_topics_interface(),
15 Node::get_node_type_descriptions_interface(), Node::get_node_waitables_interface())),
20void Component::step() {
22 this->evaluate_periodic_callbacks();
24 this->publish_outputs();
25 this->publish_predicates();
26 }
catch (
const std::exception&
ex) {
37 this->started_ =
true;
38 this->execute_thread_ = std::thread([
this]() { this->on_execute(); });
41void Component::on_execute() {
47 }
catch (
const std::exception&
ex) {
std::shared_ptr< state_representation::ParameterInterface > get_parameter(const std::string &name) const
Get a parameter by name.
virtual bool on_execute_callback()
Execute the component logic. To be redefined in derived classes.
Component(const rclcpp::NodeOptions &node_options, const std::string &fallback_name="Component")
Constructor from node options.
void execute()
Start the execution thread.
Base interface class for modulo components to wrap a ROS Node with custom behaviour.
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 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.
void add_predicate(const std::string &predicate_name, bool predicate_value)
Add a predicate to the map of predicates.
Modulo Core communication module for handling messages on publication and subscription interfaces.