Modulo 4.2.2
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Friends | List of all members
modulo_components::Component Class Reference

A wrapper for rclcpp::Node to simplify application composition through unified component interfaces. More...

#include <Component.hpp>

Inheritance diagram for modulo_components::Component:
modulo_components::ComponentInterface

Public Member Functions

 Component (const rclcpp::NodeOptions &node_options, const std::string &fallback_name="Component")
 Constructor from node options.
 
virtual ~Component ()=default
 Virtual default destructor.
 
- Public Member Functions inherited from modulo_components::ComponentInterface
virtual ~ComponentInterface ()
 Virtual destructor.
 
template<>
double get_period () const
 
template<>
std::chrono::nanoseconds get_period () const
 
template<>
rclcpp::Duration get_period () const
 

Protected Member Functions

std::shared_ptr< state_representation::ParameterInterface > get_parameter (const std::string &name) const
 Get a parameter by name.
 
void execute ()
 Start the execution thread.
 
virtual bool on_execute_callback ()
 Execute the component logic. To be redefined in derived classes.
 
template<typename DataT >
void add_output (const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::string &default_topic="", bool fixed_topic=false, bool publish_on_step=true)
 Add and configure an output signal of the component.
 
- Protected Member Functions inherited from modulo_components::ComponentInterface
 ComponentInterface (const std::shared_ptr< rclcpp::node_interfaces::NodeInterfaces< ALL_RCLCPP_NODE_INTERFACES > > &interfaces)
 Constructor with all node interfaces.
 
double get_rate () const
 Get the component rate in Hertz.
 
template<typename T >
T get_period () const
 Get the component period.
 
virtual void on_step_callback ()
 Steps to execute periodically. To be redefined by derived Component classes.
 
void add_parameter (const std::shared_ptr< state_representation::ParameterInterface > &parameter, const std::string &description, bool read_only=false)
 Add a parameter.
 
template<typename T >
void add_parameter (const std::string &name, const T &value, const std::string &description, bool read_only=false)
 Add a parameter.
 
std::shared_ptr< state_representation::ParameterInterface > get_parameter (const std::string &name) const
 Get a parameter by name.
 
template<typename T >
get_parameter_value (const std::string &name) const
 Get a parameter value by name.
 
template<typename T >
void set_parameter_value (const std::string &name, const T &value)
 Set the value of a parameter.
 
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 add_predicate (const std::string &predicate_name, bool predicate_value)
 Add a predicate to the map of predicates.
 
void add_predicate (const std::string &predicate_name, const std::function< bool(void)> &predicate_function)
 Add a predicate to the map of predicates based on a function to periodically call.
 
bool get_predicate (const std::string &predicate_name) const
 Get the logical value of a predicate.
 
void set_predicate (const std::string &predicate_name, bool predicate_value)
 Set the value of the predicate given as parameter, if the predicate is not found does not do anything.
 
void set_predicate (const std::string &predicate_name, const std::function< bool(void)> &predicate_function)
 Set the value of the predicate given as parameter, if the predicate is not found does not do anything.
 
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 triggered in which case it is set back to false immediately after it is read.
 
void trigger (const std::string &trigger_name)
 Latch the trigger with the provided name.
 
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.
 
template<typename DataT >
void add_input (const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::string &default_topic="", bool fixed_topic=false)
 Add and configure an input signal of the component.
 
template<typename DataT >
void add_input (const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::function< void()> &callback, const std::string &default_topic="", bool fixed_topic=false)
 Add and configure an input signal of the component.
 
template<typename MsgT >
void add_input (const std::string &signal_name, const std::function< void(const std::shared_ptr< MsgT >)> &callback, const std::string &default_topic="", bool fixed_topic=false)
 Add and configure an input signal of the component.
 
template<typename DataT >
std::string create_output (modulo_core::communication::PublisherType publisher_type, const std::string &signal_name, const std::shared_ptr< DataT > &data, const std::string &default_topic, bool fixed_topic, bool publish_on_step)
 Helper function to parse the signal name and add an unconfigured PublisherInterface to the map of outputs.
 
void publish_output (const std::string &signal_name)
 Trigger the publishing of an output.
 
void remove_input (const std::string &signal_name)
 Remove an input from the map of inputs.
 
void remove_output (const std::string &signal_name)
 Remove an output from the map of outputs.
 
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.
 
void add_service (const std::string &service_name, const std::function< ComponentServiceResponse(const std::string &string)> &callback)
 Add a service to trigger a callback function with a string payload.
 
void add_periodic_callback (const std::string &name, const std::function< void(void)> &callback)
 Add a periodic callback function.
 
void add_tf_broadcaster ()
 Configure a transform broadcaster.
 
void add_static_tf_broadcaster ()
 Configure a static transform broadcaster.
 
void add_tf_listener ()
 Configure a transform buffer and listener.
 
void send_transform (const state_representation::CartesianPose &transform)
 Send a transform to TF.
 
void send_transforms (const std::vector< state_representation::CartesianPose > &transforms)
 Send a vector of transforms to TF.
 
void send_static_transform (const state_representation::CartesianPose &transform)
 Send a static transform to TF.
 
void send_static_transforms (const std::vector< state_representation::CartesianPose > &transforms)
 Send a vector of static transforms to TF.
 
state_representation::CartesianPose lookup_transform (const std::string &frame, const std::string &reference_frame, const tf2::TimePoint &time_point, const tf2::Duration &duration)
 Look up a transform from TF.
 
state_representation::CartesianPose lookup_transform (const std::string &frame, const std::string &reference_frame="world", double validity_period=-1.0, const tf2::Duration &duration=tf2::Duration(std::chrono::microseconds(10)))
 Look up a transform from TF.
 
rclcpp::QoS get_qos () const
 Getter of the Quality of Service attribute.
 
void set_qos (const rclcpp::QoS &qos)
 Set the Quality of Service for ROS publishers and subscribers.
 
virtual void raise_error ()
 Put the component in error state by setting the 'in_error_state' predicate to true.
 
void publish_predicates ()
 Helper function to publish all predicates.
 
void publish_outputs ()
 Helper function to publish all output signals.
 
void evaluate_periodic_callbacks ()
 Helper function to evaluate all periodic function callbacks.
 

Friends

class ComponentPublicInterface
 

Additional Inherited Members

- Protected Attributes inherited from modulo_components::ComponentInterface
std::map< std::string, std::shared_ptr< modulo_core::communication::SubscriptionInterface > > inputs_
 Map of inputs.
 
std::map< std::string, std::shared_ptr< modulo_core::communication::PublisherInterface > > outputs_
 Map of outputs.
 
std::map< std::string, boolperiodic_outputs_
 Map of outputs with periodic publishing flag.
 

Detailed Description

A wrapper for rclcpp::Node to simplify application composition through unified component interfaces.

This class is intended for direct inheritance to implement custom components that perform one-shot or externally triggered operations. Examples of triggered behavior include providing a service, processing signals or publishing outputs on a periodic timer. One-shot behaviors may include interacting with the filesystem or publishing a predefined sequence of outputs. Developers should override on_validate_parameter_callback() if any parameters are added and on_execute_callback() to implement any one-shot behavior. In the latter case, execute() should be invoked at the end of the derived constructor.

See also
LifecycleComponent for a state-based composition alternative

Definition at line 23 of file Component.hpp.

Constructor & Destructor Documentation

◆ Component()

modulo_components::Component::Component ( const rclcpp::NodeOptions &  node_options,
const std::string &  fallback_name = "Component" 
)
explicit

Constructor from node options.

Parameters
node_optionsNode options as used in ROS2 Node
fallback_nameThe name of the component if it was not provided through the node options

Definition at line 8 of file Component.cpp.

Member Function Documentation

◆ add_output()

template<typename DataT >
void modulo_components::Component::add_output ( const std::string &  signal_name,
const std::shared_ptr< DataT > &  data,
const std::string &  default_topic = "",
bool  fixed_topic = false,
bool  publish_on_step = true 
)
inlineprotected

Add and configure an output signal of the component.

Template Parameters
DataTType of the data pointer
Parameters
signal_nameName of the output signal
dataData to transmit on the output signal
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the output signal is fixed
publish_on_stepIf true, the output is published periodically on step

Definition at line 98 of file Component.hpp.

◆ execute()

void modulo_components::Component::execute ( )
protected

Start the execution thread.

Definition at line 32 of file Component.cpp.

◆ get_parameter()

std::shared_ptr< state_representation::ParameterInterface > modulo_components::Component::get_parameter ( const std::string &  name) const
protected

Get a parameter by name.

Parameters
nameThe name of the parameter
Exceptions
modulo_core::exceptions::ParameterExceptionif the parameter could not be found
Returns
The ParameterInterface pointer to a Parameter instance

Definition at line 60 of file Component.cpp.

◆ on_execute_callback()

bool modulo_components::Component::on_execute_callback ( )
protectedvirtual

Execute the component logic. To be redefined in derived classes.

Returns
True, if the execution was successful, false otherwise

Definition at line 56 of file Component.cpp.

Friends And Related Symbol Documentation

◆ ComponentPublicInterface

friend class ComponentPublicInterface
friend

Definition at line 25 of file Component.hpp.


The documentation for this class was generated from the following files: