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

Base interface class for modulo components to wrap a ROS Node with custom behaviour. More...

#include <ComponentInterface.hpp>

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

Public Member Functions

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

 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 step ()
 Step function that is called periodically.
 
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.
 

Protected Attributes

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.
 

Friends

class ComponentInterfacePublicInterface
 

Detailed Description

Base interface class for modulo components to wrap a ROS Node with custom behaviour.

This class is not intended for direct inheritance and usage by end-users. Instead, it defines the common interfaces for the derived classes modulo_components::Component and modulo_components::LifecycleComponent.

See also
Component, LifecycleComponent

Definition at line 56 of file ComponentInterface.hpp.

Constructor & Destructor Documentation

◆ ~ComponentInterface()

modulo_components::ComponentInterface::~ComponentInterface ( )
virtual

Virtual destructor.

Definition at line 51 of file ComponentInterface.cpp.

◆ ComponentInterface()

modulo_components::ComponentInterface::ComponentInterface ( const std::shared_ptr< rclcpp::node_interfaces::NodeInterfaces< ALL_RCLCPP_NODE_INTERFACES > > &  interfaces)
explicitprotected

Constructor with all node interfaces.

Parameters
interfacesShared pointer to all the node interfaces of parent class

Definition at line 13 of file ComponentInterface.cpp.

Member Function Documentation

◆ add_input() [1/3]

template<typename MsgT >
void modulo_components::ComponentInterface::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 
)
inlineprotected

Add and configure an input signal of the component.

Template Parameters
MsgTThe ROS message type of the subscription
Parameters
signal_nameName of the input signal
callbackThe callback to use for the subscription
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the input signal is fixed

Definition at line 723 of file ComponentInterface.hpp.

◆ add_input() [2/3]

template<typename DataT >
void modulo_components::ComponentInterface::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 
)
inlineprotected

Add and configure an input signal of the component.

Template Parameters
DataTType of the data pointer
Parameters
signal_nameName of the input signal
dataData to receive on the input signal
callbackCallback function to trigger after receiving the input signal
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the input signal is fixed

Definition at line 632 of file ComponentInterface.hpp.

◆ add_input() [3/3]

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

Add and configure an input signal of the component.

Template Parameters
DataTType of the data pointer
Parameters
signal_nameName of the input signal
dataData to receive on the input signal
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the input signal is fixed

Definition at line 625 of file ComponentInterface.hpp.

◆ add_parameter() [1/2]

void modulo_components::ComponentInterface::add_parameter ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter,
const std::string &  description,
bool  read_only = false 
)
protected

Add a parameter.

This method stores a pointer reference to an existing Parameter object in the local parameter map and declares the equivalent ROS parameter on the ROS interface.

Parameters
parameterA ParameterInterface pointer to a Parameter instance
descriptionThe description of the parameter
read_onlyIf true, the value of the parameter cannot be changed after declaration
Exceptions
ParameterExceptionif the parameter could not be added

Definition at line 78 of file ComponentInterface.cpp.

◆ add_parameter() [2/2]

template<typename T >
void modulo_components::ComponentInterface::add_parameter ( const std::string &  name,
const T value,
const std::string &  description,
bool  read_only = false 
)
inlineprotected

Add a parameter.

This method creates a new Parameter object instance to reference in the local parameter map and declares the equivalent ROS parameter on the ROS interface.

Template Parameters
TThe type of the parameter
Parameters
nameThe name of the parameter
valueThe value of the parameter
descriptionThe description of the parameter
read_onlyIf true, the value of the parameter cannot be changed after declaration
Exceptions
ParameterExceptionif the parameter could not be added

Definition at line 585 of file ComponentInterface.hpp.

◆ add_periodic_callback()

void modulo_components::ComponentInterface::add_periodic_callback ( const std::string &  name,
const std::function< void(void)> &  callback 
)
protected

Add a periodic callback function.

The provided function is evaluated periodically at the component step period.

Parameters
nameThe name of the callback
callbackThe callback function that is evaluated periodically

Definition at line 449 of file ComponentInterface.cpp.

◆ add_predicate() [1/2]

void modulo_components::ComponentInterface::add_predicate ( const std::string &  predicate_name,
bool  predicate_value 
)
protected

Add a predicate to the map of predicates.

Parameters
predicate_namethe name of the associated predicate
predicate_valuethe boolean value of the predicate

Definition at line 192 of file ComponentInterface.cpp.

◆ add_predicate() [2/2]

void modulo_components::ComponentInterface::add_predicate ( const std::string &  predicate_name,
const std::function< bool(void)> &  predicate_function 
)
protected

Add a predicate to the map of predicates based on a function to periodically call.

Parameters
predicate_namethe name of the associated predicate
predicate_functionthe function to call that returns the value of the predicate

Definition at line 196 of file ComponentInterface.cpp.

◆ add_service() [1/2]

void modulo_components::ComponentInterface::add_service ( const std::string &  service_name,
const std::function< ComponentServiceResponse(const std::string &string)> &  callback 
)
protected

Add a service to trigger a callback function with a string payload.

The string payload can have an arbitrary format to parameterize and control the callback behaviour as desired. It is the responsibility of the service callback to parse the string according to some payload format. When adding a service with a string payload, be sure to document the payload format appropriately.

Parameters
service_nameThe name of the service
callbackA service callback function with a string argument that returns a ComponentServiceResponse

Definition at line 396 of file ComponentInterface.cpp.

◆ add_service() [2/2]

void modulo_components::ComponentInterface::add_service ( const std::string &  service_name,
const std::function< ComponentServiceResponse(void)> &  callback 
)
protected

Add a service to trigger a callback function with no input arguments.

Parameters
service_nameThe name of the service
callbackA service callback function with no arguments that returns a ComponentServiceResponse

Definition at line 369 of file ComponentInterface.cpp.

◆ add_static_tf_broadcaster()

void modulo_components::ComponentInterface::add_static_tf_broadcaster ( )
protected

Configure a static transform broadcaster.

Definition at line 475 of file ComponentInterface.cpp.

◆ add_tf_broadcaster()

void modulo_components::ComponentInterface::add_tf_broadcaster ( )
protected

Configure a transform broadcaster.

Definition at line 464 of file ComponentInterface.cpp.

◆ add_tf_listener()

void modulo_components::ComponentInterface::add_tf_listener ( )
protected

Configure a transform buffer and listener.

Definition at line 488 of file ComponentInterface.cpp.

◆ add_trigger()

void modulo_components::ComponentInterface::add_trigger ( const std::string &  trigger_name)
protected

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.

Parameters
trigger_nameThe name of the trigger

Definition at line 255 of file ComponentInterface.cpp.

◆ create_output()

template<typename DataT >
std::string modulo_components::ComponentInterface::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 
)
inlineprotected

Helper function to parse the signal name and add an unconfigured PublisherInterface to the map of outputs.

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
Exceptions
modulo_core::exceptions::AddSignalExceptionif the output could not be created (empty name, already registered)
Returns
The parsed signal name

Definition at line 746 of file ComponentInterface.hpp.

◆ declare_input()

void modulo_components::ComponentInterface::declare_input ( const std::string &  signal_name,
const std::string &  default_topic = "",
bool  fixed_topic = false 
)
protected

Declare an input to create the topic parameter without adding it to the map of inputs yet.

Parameters
signal_nameThe signal name of the input
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the signal is fixed
Exceptions
modulo_core::exceptions::AddSignalExceptionif the input could not be declared (empty name or already created)

Definition at line 288 of file ComponentInterface.cpp.

◆ declare_output()

void modulo_components::ComponentInterface::declare_output ( const std::string &  signal_name,
const std::string &  default_topic = "",
bool  fixed_topic = false 
)
protected

Declare an output to create the topic parameter without adding it to the map of outputs yet.

Parameters
signal_nameThe signal name of the output
default_topicIf set, the default value for the topic name to use
fixed_topicIf true, the topic name of the signal is fixed
Exceptions
modulo_core::exceptions::AddSignalExceptionif the output could not be declared (empty name or already created)

Definition at line 293 of file ComponentInterface.cpp.

◆ evaluate_periodic_callbacks()

void modulo_components::ComponentInterface::evaluate_periodic_callbacks ( )
protected

Helper function to evaluate all periodic function callbacks.

Definition at line 603 of file ComponentInterface.cpp.

◆ get_parameter()

std::shared_ptr< state_representation::ParameterInterface > modulo_components::ComponentInterface::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 125 of file ComponentInterface.cpp.

◆ get_parameter_value()

template<typename T >
T modulo_components::ComponentInterface::get_parameter_value ( const std::string &  name) const
inlineprotected

Get a parameter value by name.

Template Parameters
TThe type of the parameter
Parameters
nameThe name of the parameter
Exceptions
modulo_core::exceptions::ParameterExceptionif the parameter value could not be accessed
Returns
The value of the parameter

Definition at line 595 of file ComponentInterface.hpp.

◆ get_period() [1/4]

template<typename T >
T modulo_components::ComponentInterface::get_period ( ) const
protected

Get the component period.

Returns
The component period

◆ get_period() [2/4]

template<>
double modulo_components::ComponentInterface::get_period ( ) const

Definition at line 60 of file ComponentInterface.cpp.

◆ get_period() [3/4]

template<>
std::chrono::nanoseconds modulo_components::ComponentInterface::get_period ( ) const

Definition at line 65 of file ComponentInterface.cpp.

◆ get_period() [4/4]

template<>
rclcpp::Duration modulo_components::ComponentInterface::get_period ( ) const

Definition at line 70 of file ComponentInterface.cpp.

◆ get_predicate()

bool modulo_components::ComponentInterface::get_predicate ( const std::string &  predicate_name) const
protected

Get the logical value of a predicate.

If the predicate is not found or the callable function fails, the return value is false.

Parameters
predicate_namethe name of the predicate to retrieve from the map of predicates
Returns
the value of the predicate as a boolean

Definition at line 218 of file ComponentInterface.cpp.

◆ get_qos()

rclcpp::QoS modulo_components::ComponentInterface::get_qos ( ) const
protected

Getter of the Quality of Service attribute.

Returns
The Quality of Service attribute

Definition at line 551 of file ComponentInterface.cpp.

◆ get_rate()

double modulo_components::ComponentInterface::get_rate ( ) const
protected

Get the component rate in Hertz.

Returns
The component rate

Definition at line 55 of file ComponentInterface.cpp.

◆ lookup_transform() [1/2]

state_representation::CartesianPose modulo_components::ComponentInterface::lookup_transform ( const std::string &  frame,
const std::string &  reference_frame,
const tf2::TimePoint &  time_point,
const tf2::Duration &  duration 
)
protected

Look up a transform from TF.

Parameters
frameThe desired frame of the transform
reference_frameThe desired reference frame of the transform
time_pointThe time at which the value of the transform is desired
durationHow long to block the lookup call before failing
Exceptions
modulo_core::exceptions::LookupTransformExceptionif TF buffer/listener are unconfigured or if the lookupTransform call failed
Returns
If it exists, the requested transform

Definition at line 515 of file ComponentInterface.cpp.

◆ lookup_transform() [2/2]

state_representation::CartesianPose modulo_components::ComponentInterface::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)) 
)
protected

Look up a transform from TF.

Parameters
frameThe desired frame of the transform
reference_frameThe desired reference frame of the transform
validity_periodThe validity period of the latest transform from the time of lookup in seconds
durationHow long to block the lookup call before failing
Exceptions
modulo_core::exceptions::LookupTransformExceptionif TF buffer/listener are unconfigured, if the lookupTransform call failed, or if the transform is too old
Returns
If it exists and is still valid, the requested transform

Definition at line 524 of file ComponentInterface.cpp.

◆ on_step_callback()

void modulo_components::ComponentInterface::on_step_callback ( )
protectedvirtual

Steps to execute periodically. To be redefined by derived Component classes.

Definition at line 76 of file ComponentInterface.cpp.

◆ on_validate_parameter_callback()

bool modulo_components::ComponentInterface::on_validate_parameter_callback ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter)
protectedvirtual

Parameter validation function to be redefined by derived Component classes.

This method is automatically invoked whenever the ROS interface tried to modify a parameter. Validation and sanitization can be performed by reading or writing the value of the parameter through the ParameterInterface pointer, depending on the parameter name and desired component behaviour. If the validation returns true, the updated parameter value (including any modifications) is applied. If the validation returns false, any changes to the parameter are discarded and the parameter value is not changed.

Parameters
parameterA ParameterInterface pointer to a Parameter instance
Returns
The validation result

Definition at line 187 of file ComponentInterface.cpp.

◆ publish_output()

void modulo_components::ComponentInterface::publish_output ( const std::string &  signal_name)
protected

Trigger the publishing of an output.

Parameters
signal_nameThe name of the output signal
Exceptions
ComponentExceptionif the output is being published periodically or if the signal name could not be found

Definition at line 330 of file ComponentInterface.cpp.

◆ publish_outputs()

void modulo_components::ComponentInterface::publish_outputs ( )
protected

Helper function to publish all output signals.

Definition at line 589 of file ComponentInterface.cpp.

◆ publish_predicates()

void modulo_components::ComponentInterface::publish_predicates ( )
protected

Helper function to publish all predicates.

Definition at line 577 of file ComponentInterface.cpp.

◆ raise_error()

void modulo_components::ComponentInterface::raise_error ( )
protectedvirtual

Put the component in error state by setting the 'in_error_state' predicate to true.

Definition at line 559 of file ComponentInterface.cpp.

◆ remove_input()

void modulo_components::ComponentInterface::remove_input ( const std::string &  signal_name)
protected

Remove an input from the map of inputs.

Parameters
signal_nameThe name of the input

Definition at line 347 of file ComponentInterface.cpp.

◆ remove_output()

void modulo_components::ComponentInterface::remove_output ( const std::string &  signal_name)
protected

Remove an output from the map of outputs.

Parameters
signal_nameThe name of the output

Definition at line 358 of file ComponentInterface.cpp.

◆ send_static_transform()

void modulo_components::ComponentInterface::send_static_transform ( const state_representation::CartesianPose &  transform)
protected

Send a static transform to TF.

Parameters
transformThe transform to send

Definition at line 507 of file ComponentInterface.cpp.

◆ send_static_transforms()

void modulo_components::ComponentInterface::send_static_transforms ( const std::vector< state_representation::CartesianPose > &  transforms)
protected

Send a vector of static transforms to TF.

Parameters
transformsThe vector of transforms to send

Definition at line 511 of file ComponentInterface.cpp.

◆ send_transform()

void modulo_components::ComponentInterface::send_transform ( const state_representation::CartesianPose &  transform)
protected

Send a transform to TF.

Parameters
transformThe transform to send

Definition at line 499 of file ComponentInterface.cpp.

◆ send_transforms()

void modulo_components::ComponentInterface::send_transforms ( const std::vector< state_representation::CartesianPose > &  transforms)
protected

Send a vector of transforms to TF.

Parameters
transformsThe vector of transforms to send

Definition at line 503 of file ComponentInterface.cpp.

◆ set_parameter_value()

template<typename T >
void modulo_components::ComponentInterface::set_parameter_value ( const std::string &  name,
const T value 
)
inlineprotected

Set the value of a parameter.

The parameter must have been previously declared. This method preserves the reference to the original Parameter instance

Template Parameters
TThe type of the parameter
Parameters
nameThe name of the parameter
Returns
The value of the parameter

Definition at line 605 of file ComponentInterface.hpp.

◆ set_predicate() [1/2]

void modulo_components::ComponentInterface::set_predicate ( const std::string &  predicate_name,
bool  predicate_value 
)
protected

Set the value of the predicate given as parameter, if the predicate is not found does not do anything.

Even though the predicates are published periodically, the new value of this predicate will be published once immediately after setting it.

Parameters
predicate_namethe name of the predicate to retrieve from the map of predicates
predicate_valuethe new value of the predicate

Definition at line 236 of file ComponentInterface.cpp.

◆ set_predicate() [2/2]

void modulo_components::ComponentInterface::set_predicate ( const std::string &  predicate_name,
const std::function< bool(void)> &  predicate_function 
)
protected

Set the value of the predicate given as parameter, if the predicate is not found does not do anything.

Even though the predicates are published periodically, the new value of this predicate will be published once immediately after setting it.

Parameters
predicate_namethe name of the predicate to retrieve from the map of predicates
predicate_functionthe function to call that returns the value of the predicate

Definition at line 240 of file ComponentInterface.cpp.

◆ set_qos()

void modulo_components::ComponentInterface::set_qos ( const rclcpp::QoS &  qos)
protected

Set the Quality of Service for ROS publishers and subscribers.

Parameters
qosThe desired Quality of Service

Definition at line 555 of file ComponentInterface.cpp.

◆ step()

void modulo_components::ComponentInterface::step ( )
protectedvirtual

Step function that is called periodically.

Definition at line 74 of file ComponentInterface.cpp.

◆ trigger()

void modulo_components::ComponentInterface::trigger ( const std::string &  trigger_name)
protected

Latch the trigger with the provided name.

Parameters
trigger_nameThe name of the trigger

Definition at line 276 of file ComponentInterface.cpp.

Friends And Related Symbol Documentation

◆ ComponentInterfacePublicInterface

Definition at line 58 of file ComponentInterface.hpp.

Member Data Documentation

◆ inputs_

std::map<std::string, std::shared_ptr<modulo_core::communication::SubscriptionInterface> > modulo_components::ComponentInterface::inputs_
protected

Map of inputs.

Definition at line 440 of file ComponentInterface.hpp.

◆ outputs_

std::map<std::string, std::shared_ptr<modulo_core::communication::PublisherInterface> > modulo_components::ComponentInterface::outputs_
protected

Map of outputs.

Definition at line 441 of file ComponentInterface.hpp.

◆ periodic_outputs_

std::map<std::string, bool> modulo_components::ComponentInterface::periodic_outputs_
protected

Map of outputs with periodic publishing flag.

Definition at line 442 of file ComponentInterface.hpp.


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