Modulo 5.0.0
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | List of all members
modulo_controllers::BaseControllerInterface Class Reference

Base controller class to combine ros2_control, control libraries and modulo. More...

#include <BaseControllerInterface.hpp>

Inheritance diagram for modulo_controllers::BaseControllerInterface:
modulo_controllers::ControllerInterface modulo_controllers::RobotControllerInterface

Public Member Functions

 BaseControllerInterface ()
 Default constructor.
 
CallbackReturn on_init () override
 Declare parameters and register the on_set_parameters callback.
 
CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
 Add signals.
 
template<>
void write_output (const std::string &name, const bool &data)
 
template<>
void write_output (const std::string &name, const double &data)
 
template<>
void write_output (const std::string &name, const std::vector< double > &data)
 
template<>
void write_output (const std::string &name, const int &data)
 
template<>
void write_output (const std::string &name, const std::string &data)
 

Protected Member Functions

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.
 
virtual bool on_validate_parameter_callback (const std::shared_ptr< state_representation::ParameterInterface > &parameter)
 Parameter validation function to be redefined by derived controller classes.
 
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.
 
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 controller.
 
void trigger (const std::string &trigger_name)
 Latch the trigger with the provided name.
 
template<typename T >
void add_input (const std::string &name, const std::string &topic_name="")
 Add an input to the controller.
 
template<typename T >
void add_output (const std::string &name, const std::string &topic_name="")
 Add an output to the controller.
 
void set_input_validity_period (double input_validity_period)
 Set the input validity period of input signals.
 
template<typename T >
std::optional< Tread_input (const std::string &name)
 Read the most recent message of an input.
 
template<typename T >
void write_output (const std::string &name, const T &data)
 Write an object to an output.
 
void add_service (const std::string &service_name, const std::function< ControllerServiceResponse(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< ControllerServiceResponse(const std::string &string)> &callback)
 Add a service to trigger a callback function with a string payload.
 
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.
 
bool is_active () const
 Check if the controller is currently in state active or not.
 
std::timed_mutex & get_command_mutex ()
 Get the reference to the command mutex.
 
template<>
void add_input (const std::string &name, const std::string &topic_name)
 
template<>
void add_input (const std::string &name, const std::string &topic_name)
 
template<>
void add_input (const std::string &name, const std::string &topic_name)
 
template<>
void add_output (const std::string &name, const std::string &topic_name)
 
template<>
void add_output (const std::string &name, const std::string &topic_name)
 
template<>
void add_output (const std::string &name, const std::string &topic_name)
 
template<>
std::optional< boolread_input (const std::string &name)
 
template<>
std::optional< doubleread_input (const std::string &name)
 
template<>
std::optional< intread_input (const std::string &name)
 

Detailed Description

Base controller class to combine ros2_control, control libraries and modulo.

Definition at line 105 of file BaseControllerInterface.hpp.

Constructor & Destructor Documentation

◆ BaseControllerInterface()

modulo_controllers::BaseControllerInterface::BaseControllerInterface ( )

Default constructor.

Definition at line 22 of file BaseControllerInterface.cpp.

Member Function Documentation

◆ add_input() [1/4]

template<>
void modulo_controllers::BaseControllerInterface::add_input ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 562 of file BaseControllerInterface.hpp.

◆ add_input() [2/4]

template<>
void modulo_controllers::BaseControllerInterface::add_input ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 569 of file BaseControllerInterface.hpp.

◆ add_input() [3/4]

template<>
void modulo_controllers::BaseControllerInterface::add_input ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 584 of file BaseControllerInterface.hpp.

◆ add_input() [4/4]

template<typename T >
void modulo_controllers::BaseControllerInterface::add_input ( const std::string &  name,
const std::string &  topic_name = "" 
)
inlineprotected

Add an input to the controller.

Inputs should be added in the on_init function of the derived controllers. Doing this will create a ROS 2 subscription for the message type.

Template Parameters
TThe type of the input data
Parameters
nameThe name of the input
topic_nameThe topic name of the input (defaults to ~/name)

Definition at line 528 of file BaseControllerInterface.hpp.

◆ add_output() [1/4]

template<>
void modulo_controllers::BaseControllerInterface::add_output ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 627 of file BaseControllerInterface.hpp.

◆ add_output() [2/4]

template<>
void modulo_controllers::BaseControllerInterface::add_output ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 632 of file BaseControllerInterface.hpp.

◆ add_output() [3/4]

template<>
void modulo_controllers::BaseControllerInterface::add_output ( const std::string &  name,
const std::string &  topic_name 
)
inlineprotected

Definition at line 643 of file BaseControllerInterface.hpp.

◆ add_output() [4/4]

template<typename T >
void modulo_controllers::BaseControllerInterface::add_output ( const std::string &  name,
const std::string &  topic_name = "" 
)
inlineprotected

Add an output to the controller.

Outputs should be added in the on_init function of the derived controllers. Doing this will create a ROS 2 publisher for the message type and wrap it in a RealtimePublisher.

Template Parameters
TThe type of the output data
Parameters
nameThe name of the output
topic_nameThe topic name of the output (defaults to ~/name)

Definition at line 607 of file BaseControllerInterface.hpp.

◆ add_parameter() [1/2]

void modulo_controllers::BaseControllerInterface::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

◆ add_parameter() [2/2]

template<typename T >
void modulo_controllers::BaseControllerInterface::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

Definition at line 488 of file BaseControllerInterface.hpp.

◆ add_predicate() [1/2]

void modulo_controllers::BaseControllerInterface::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 168 of file BaseControllerInterface.cpp.

◆ add_predicate() [2/2]

void modulo_controllers::BaseControllerInterface::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 172 of file BaseControllerInterface.cpp.

◆ add_service() [1/2]

void modulo_controllers::BaseControllerInterface::add_service ( const std::string &  service_name,
const std::function< ControllerServiceResponse(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 ControllerServiceResponse

Definition at line 508 of file BaseControllerInterface.cpp.

◆ add_service() [2/2]

void modulo_controllers::BaseControllerInterface::add_service ( const std::string &  service_name,
const std::function< ControllerServiceResponse(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 ControllerServiceResponse

Definition at line 475 of file BaseControllerInterface.cpp.

◆ add_trigger()

void modulo_controllers::BaseControllerInterface::add_trigger ( const std::string &  trigger_name)
protected

Add a trigger to the controller.

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 230 of file BaseControllerInterface.cpp.

◆ get_command_mutex()

std::timed_mutex & modulo_controllers::BaseControllerInterface::get_command_mutex ( )
protected

Get the reference to the command mutex.

Returns
The reference to the command mutex

Definition at line 554 of file BaseControllerInterface.cpp.

◆ get_parameter()

std::shared_ptr< ParameterInterface > modulo_controllers::BaseControllerInterface::get_parameter ( const std::string &  name) const
protected

Get a parameter by name.

Parameters
nameThe name of the parameter
Returns
The ParameterInterface pointer to a Parameter instance

Definition at line 102 of file BaseControllerInterface.cpp.

◆ get_parameter_value()

template<typename T >
T modulo_controllers::BaseControllerInterface::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
Returns
The value of the parameter

Definition at line 498 of file BaseControllerInterface.hpp.

◆ get_predicate()

bool modulo_controllers::BaseControllerInterface::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 193 of file BaseControllerInterface.cpp.

◆ get_qos()

rclcpp::QoS modulo_controllers::BaseControllerInterface::get_qos ( ) const
protected

Getter of the Quality of Service attribute.

Returns
The Quality of Service attribute

Definition at line 542 of file BaseControllerInterface.cpp.

◆ is_active()

bool modulo_controllers::BaseControllerInterface::is_active ( ) const
protected

Check if the controller is currently in state active or not.

Returns
True if the controller is active, false otherwise

Definition at line 550 of file BaseControllerInterface.cpp.

◆ on_configure()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn modulo_controllers::BaseControllerInterface::on_configure ( const rclcpp_lifecycle::State &  previous_state)
override

Add signals.

Parameters
previous_stateThe previous lifecycle state
Returns
SUCCESS or ERROR

Definition at line 39 of file BaseControllerInterface.cpp.

◆ on_init()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn modulo_controllers::BaseControllerInterface::on_init ( )
override

Declare parameters and register the on_set_parameters callback.

Returns
CallbackReturn status

Definition at line 25 of file BaseControllerInterface.cpp.

◆ on_validate_parameter_callback()

bool modulo_controllers::BaseControllerInterface::on_validate_parameter_callback ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter)
protectedvirtual

Parameter validation function to be redefined by derived controller 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 controller 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

Reimplemented in modulo_controllers::RobotControllerInterface.

Definition at line 164 of file BaseControllerInterface.cpp.

◆ read_input() [1/4]

template<typename T >
std::optional< T > modulo_controllers::BaseControllerInterface::read_input ( const std::string &  name)
inlineprotected

Read the most recent message of an input.

Template Parameters
TThe expected type of the input data
Parameters
nameThe name of the input
Returns
The data on the desired input channel if the input exists and is not older than parameter 'input_validity_period'

Definition at line 653 of file BaseControllerInterface.hpp.

◆ read_input() [2/4]

template<>
std::optional< int > modulo_controllers::BaseControllerInterface::read_input ( const std::string &  name)
inlineprotected

Definition at line 653 of file BaseControllerInterface.hpp.

◆ read_input() [3/4]

template<>
std::optional< double > modulo_controllers::BaseControllerInterface::read_input ( const std::string &  name)
inlineprotected

Definition at line 653 of file BaseControllerInterface.hpp.

◆ read_input() [4/4]

template<>
std::optional< bool > modulo_controllers::BaseControllerInterface::read_input ( const std::string &  name)
inlineprotected

Definition at line 653 of file BaseControllerInterface.hpp.

◆ set_input_validity_period()

void modulo_controllers::BaseControllerInterface::set_input_validity_period ( double  input_validity_period)
protected

Set the input validity period of input signals.

Parameters
input_validity_periodThe desired input validity period

Definition at line 421 of file BaseControllerInterface.cpp.

◆ set_parameter_value()

template<typename T >
void modulo_controllers::BaseControllerInterface::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 508 of file BaseControllerInterface.hpp.

◆ set_predicate() [1/2]

void modulo_controllers::BaseControllerInterface::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 211 of file BaseControllerInterface.cpp.

◆ set_predicate() [2/2]

void modulo_controllers::BaseControllerInterface::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 215 of file BaseControllerInterface.cpp.

◆ set_qos()

void modulo_controllers::BaseControllerInterface::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 546 of file BaseControllerInterface.cpp.

◆ trigger()

void modulo_controllers::BaseControllerInterface::trigger ( const std::string &  trigger_name)
protected

Latch the trigger with the provided name.

Parameters
trigger_nameThe name of the trigger

Definition at line 251 of file BaseControllerInterface.cpp.

◆ write_output() [1/6]

template<>
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const bool data 
)
inline

Definition at line 846 of file BaseControllerInterface.hpp.

◆ write_output() [2/6]

template<>
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const double data 
)
inline

Definition at line 851 of file BaseControllerInterface.hpp.

◆ write_output() [3/6]

template<>
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const int data 
)
inline

Definition at line 861 of file BaseControllerInterface.hpp.

◆ write_output() [4/6]

template<>
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const std::string &  data 
)
inline

Definition at line 866 of file BaseControllerInterface.hpp.

◆ write_output() [5/6]

template<>
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const std::vector< double > &  data 
)
inline

Definition at line 856 of file BaseControllerInterface.hpp.

◆ write_output() [6/6]

template<typename T >
void modulo_controllers::BaseControllerInterface::write_output ( const std::string &  name,
const T data 
)
inlineprotected

Write an object to an output.

This uses the realtime publisher from add_output() to simplify publishing data in the realtime context of the control loop.

Template Parameters
TThe type of the the object to publish
Parameters
nameThe name of the output
stateThe object to publish

Definition at line 753 of file BaseControllerInterface.hpp.


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