Modulo 5.0.0
|
A wrapper for rclcpp_lifecycle::LifecycleNode to simplify application composition through unified component interfaces while supporting lifecycle states and transitions. More...
#include <LifecycleComponent.hpp>
Public Member Functions | |
LifecycleComponent (const rclcpp::NodeOptions &node_options, const std::string &fallback_name="LifecycleComponent") | |
Constructor from node options. | |
virtual | ~LifecycleComponent ()=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. | |
virtual bool | on_configure_callback () |
Steps to execute when configuring the component. | |
virtual bool | on_cleanup_callback () |
Steps to execute when cleaning up the component. | |
virtual bool | on_activate_callback () |
Steps to execute when activating the component. | |
virtual bool | on_deactivate_callback () |
Steps to execute when deactivating the component. | |
virtual bool | on_shutdown_callback () |
Steps to execute when shutting down the component. | |
virtual bool | on_error_callback () |
Steps to execute when handling errors. | |
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 an output signal of the component. | |
rclcpp_lifecycle::State | get_lifecycle_state () const |
Get the current lifecycle state of the component. | |
void | raise_error () override |
Trigger the shutdown and error transitions. | |
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 > ¶meter, 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 > | |
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 > ¶meter) |
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. | |
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. | |
void | finalize_interfaces () |
Finalize all interfaces. | |
Friends | |
class | LifecycleComponentPublicInterface |
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, bool > | periodic_outputs_ |
Map of outputs with periodic publishing flag. | |
A wrapper for rclcpp_lifecycle::LifecycleNode to simplify application composition through unified component interfaces while supporting lifecycle states and transitions.
This class is intended for direct inheritance to implement custom state-based components that perform different behaviors based on their state and on state transitions. An example of state-based behaviour is a signal component that requires configuration steps to determine which inputs to register and subsequently should publish outputs only when the component is activated. Developers should override on_validate_parameter_callback() if any parameters are added. In addition, the following state transition callbacks should be overridden whenever custom transition behavior is needed:
Definition at line 29 of file LifecycleComponent.hpp.
|
explicit |
Constructor from node options.
node_options | Node options as used in ROS2 LifecycleNode |
fallback_name | The name of the component if it was not provided through the node options |
Definition at line 8 of file LifecycleComponent.cpp.
|
inlineprotected |
Add an output signal of the component.
DataT | Type of the data pointer |
signal_name | Name of the output signal |
data | Data to transmit on the output signal |
default_topic | If set, the default value for the topic name to use |
fixed_topic | If true, the topic name of the output signal is fixed |
publish_on_step | If true, the output is published periodically on step |
Definition at line 287 of file LifecycleComponent.hpp.
|
protected |
Get the current lifecycle state of the component.
Definition at line 333 of file LifecycleComponent.cpp.
|
protected |
Get a parameter by name.
name | The name of the parameter |
modulo_core::exceptions::ParameterException | if the parameter could not be found |
Definition at line 20 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when activating the component.
This method can be overridden by derived Component classes. Activation generally involves final setup steps before the on_step callback is periodically evaluated.
Definition at line 131 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when cleaning up the component.
This method can be overridden by derived Component classes. Cleanup generally involves resetting the properties and states to initial conditions.
Definition at line 96 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when configuring the component.
This method can be overridden by derived Component classes. Configuration generally involves reading parameters and adding inputs and outputs.
Definition at line 70 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when deactivating the component.
This method can be overridden by derived Component classes. Deactivation generally involves any steps to reset the component to an inactive state.
Definition at line 158 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when handling errors.
This method can be overridden by derived Component classes. Error handling generally involves recovering and resetting the component to an unconfigured state.
Definition at line 232 of file LifecycleComponent.cpp.
|
protectedvirtual |
Steps to execute when shutting down the component.
This method can be overridden by derived Component classes. Shutdown generally involves the destruction of any threads or properties not handled by the base class.
Definition at line 206 of file LifecycleComponent.cpp.
|
overrideprotectedvirtual |
Trigger the shutdown and error transitions.
Reimplemented from modulo_components::ComponentInterface.
Definition at line 337 of file LifecycleComponent.cpp.
Definition at line 31 of file LifecycleComponent.hpp.