Modulo 5.0.0
|
Base controller class to combine ros2_control, control libraries and modulo. More...
#include <BaseControllerInterface.hpp>
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 > ¶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. | |
virtual bool | on_validate_parameter_callback (const std::shared_ptr< state_representation::ParameterInterface > ¶meter) |
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 > | |
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< T > | read_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< bool > | read_input (const std::string &name) |
template<> | |
std::optional< double > | read_input (const std::string &name) |
template<> | |
std::optional< int > | read_input (const std::string &name) |
Base controller class to combine ros2_control, control libraries and modulo.
Definition at line 105 of file BaseControllerInterface.hpp.
modulo_controllers::BaseControllerInterface::BaseControllerInterface | ( | ) |
Default constructor.
Definition at line 22 of file BaseControllerInterface.cpp.
|
inlineprotected |
Definition at line 562 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 569 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 584 of file BaseControllerInterface.hpp.
|
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.
T | The type of the input data |
name | The name of the input |
topic_name | The topic name of the input (defaults to ~/name) |
Definition at line 528 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 627 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 632 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 643 of file BaseControllerInterface.hpp.
|
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.
T | The type of the output data |
name | The name of the output |
topic_name | The topic name of the output (defaults to ~/name) |
Definition at line 607 of file BaseControllerInterface.hpp.
|
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.
parameter | A ParameterInterface pointer to a Parameter instance |
description | The description of the parameter |
read_only | If true, the value of the parameter cannot be changed after declaration |
|
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.
T | The type of the parameter |
name | The name of the parameter |
value | The value of the parameter |
description | The description of the parameter |
read_only | If true, the value of the parameter cannot be changed after declaration |
Definition at line 488 of file BaseControllerInterface.hpp.
|
protected |
Add a predicate to the map of predicates.
predicate_name | the name of the associated predicate |
predicate_value | the boolean value of the predicate |
Definition at line 168 of file BaseControllerInterface.cpp.
|
protected |
Add a predicate to the map of predicates based on a function to periodically call.
predicate_name | the name of the associated predicate |
predicate_function | the function to call that returns the value of the predicate |
Definition at line 172 of file BaseControllerInterface.cpp.
|
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.
service_name | The name of the service |
callback | A service callback function with a string argument that returns a ControllerServiceResponse |
Definition at line 508 of file BaseControllerInterface.cpp.
|
protected |
Add a service to trigger a callback function with no input arguments.
service_name | The name of the service |
callback | A service callback function with no arguments that returns a ControllerServiceResponse |
Definition at line 475 of file BaseControllerInterface.cpp.
|
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.
trigger_name | The name of the trigger |
Definition at line 230 of file BaseControllerInterface.cpp.
|
protected |
Get the reference to the command mutex.
Definition at line 554 of file BaseControllerInterface.cpp.
|
protected |
Get a parameter by name.
name | The name of the parameter |
Definition at line 102 of file BaseControllerInterface.cpp.
|
inlineprotected |
Get a parameter value by name.
T | The type of the parameter |
name | The name of the parameter |
Definition at line 498 of file BaseControllerInterface.hpp.
|
protected |
Get the logical value of a predicate.
If the predicate is not found or the callable function fails, the return value is false.
predicate_name | the name of the predicate to retrieve from the map of predicates |
Definition at line 193 of file BaseControllerInterface.cpp.
|
protected |
Getter of the Quality of Service attribute.
Definition at line 542 of file BaseControllerInterface.cpp.
|
protected |
Check if the controller is currently in state active or not.
Definition at line 550 of file BaseControllerInterface.cpp.
|
override |
Add signals.
previous_state | The previous lifecycle state |
Definition at line 39 of file BaseControllerInterface.cpp.
|
override |
Declare parameters and register the on_set_parameters callback.
Definition at line 25 of file BaseControllerInterface.cpp.
|
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.
parameter | A ParameterInterface pointer to a Parameter instance |
Reimplemented in modulo_controllers::RobotControllerInterface.
Definition at line 164 of file BaseControllerInterface.cpp.
|
inlineprotected |
Read the most recent message of an input.
T | The expected type of the input data |
name | The name of the input |
Definition at line 653 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 653 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 653 of file BaseControllerInterface.hpp.
|
inlineprotected |
Definition at line 653 of file BaseControllerInterface.hpp.
|
protected |
Set the input validity period of input signals.
input_validity_period | The desired input validity period |
Definition at line 421 of file BaseControllerInterface.cpp.
|
inlineprotected |
Set the value of a parameter.
The parameter must have been previously declared. This method preserves the reference to the original Parameter instance
T | The type of the parameter |
name | The name of the parameter |
Definition at line 508 of file BaseControllerInterface.hpp.
|
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.
predicate_name | the name of the predicate to retrieve from the map of predicates |
predicate_value | the new value of the predicate |
Definition at line 211 of file BaseControllerInterface.cpp.
|
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.
predicate_name | the name of the predicate to retrieve from the map of predicates |
predicate_function | the function to call that returns the value of the predicate |
Definition at line 215 of file BaseControllerInterface.cpp.
Set the Quality of Service for ROS publishers and subscribers.
qos | The desired Quality of Service |
Definition at line 546 of file BaseControllerInterface.cpp.
|
protected |
Latch the trigger with the provided name.
trigger_name | The name of the trigger |
Definition at line 251 of file BaseControllerInterface.cpp.
|
inline |
Definition at line 846 of file BaseControllerInterface.hpp.
|
inline |
Definition at line 851 of file BaseControllerInterface.hpp.
|
inline |
Definition at line 861 of file BaseControllerInterface.hpp.
|
inline |
Definition at line 866 of file BaseControllerInterface.hpp.
|
inline |
Definition at line 856 of file BaseControllerInterface.hpp.
|
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.
T | The type of the the object to publish |
name | The name of the output |
state | The object to publish |
Definition at line 753 of file BaseControllerInterface.hpp.