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

Base controller class that automatically associates joints with a JointState object. More...

#include <RobotControllerInterface.hpp>

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

Public Member Functions

 RobotControllerInterface ()
 Default constructor.
 
 RobotControllerInterface (bool robot_model_required, const std::string &control_type="", bool load_geometries=false)
 Constructor with robot model flag and a control type to determine the command interfaces to claim.
 
CallbackReturn add_interfaces () override
 Add interfaces like parameters, signals, services, and predicates to the controller.
 
CallbackReturn on_configure () override
 Configure the controller.
 
CallbackReturn on_activate () override
 Activate the controller.
 
- Public Member Functions inherited from modulo_controllers::ControllerInterface
 ControllerInterface (bool claim_all_state_interfaces=false)
 Default constructor.
 
CallbackReturn on_init () override
 Declare parameters.
 
CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) final
 Set class properties from parameters.
 
CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) final
 Initialize internal data attributes from configured interfaces and wait for valid states from hardware.
 
CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) final
 Deactivate the controller.
 
controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) final
 Read the state interfaces, perform control evaluation and write the command interfaces.
 
controller_interface::InterfaceConfiguration state_interface_configuration () const final
 Configure the state interfaces.
 
controller_interface::InterfaceConfiguration command_interface_configuration () const final
 Configure the command interfaces.
 
- Public Member Functions inherited from modulo_controllers::BaseControllerInterface
 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

const state_representation::JointState & get_joint_state ()
 Access the joint state object.
 
const state_representation::CartesianState & get_cartesian_state ()
 Access the Cartesian state object.
 
const state_representation::CartesianWrench & get_ft_sensor ()
 Access the Cartesian wrench object.
 
void compute_cartesian_state ()
 Compute the Cartesian state from forward kinematics of the current joint state.
 
void set_joint_command (const state_representation::JointState &joint_command)
 Set the joint command object.
 
bool on_validate_parameter_callback (const std::shared_ptr< state_representation::ParameterInterface > &parameter) override
 Parameter validation function to be redefined by derived controller classes.
 
- Protected Member Functions inherited from modulo_controllers::ControllerInterface
virtual CallbackReturn on_deactivate ()
 Deactivate the controller.
 
virtual controller_interface::return_type evaluate (const rclcpp::Time &time, const std::chrono::nanoseconds &period)=0
 The control logic callback.
 
void add_state_interface (const std::string &name, const std::string &interface)
 Add a state interface to the controller by name.
 
void add_command_interface (const std::string &name, const std::string &interface)
 Add a command interface to the controller by name.
 
std::unordered_map< std::string, doubleget_state_interfaces (const std::string &name) const
 Get a map containing the state interfaces by name of the parent tag.
 
double get_state_interface (const std::string &name, const std::string &interface) const
 Get the value of a state interface by name.
 
double get_command_interface (const std::string &name, const std::string &interface) const
 Get the value of a command interface by name.
 
void set_command_interface (const std::string &name, const std::string &interface, double value)
 Set the value of a command interface by name.
 
- Protected Member Functions inherited from modulo_controllers::BaseControllerInterface
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.
 
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)
 

Protected Attributes

std::shared_ptr< robot_model::Model > robot_
 Robot model object generated from URDF.
 
std::string task_space_frame_
 The frame in task space for forward kinematics calculations, if applicable.
 
std::string ft_sensor_name_
 The name of a force torque sensor in the hardware description.
 
std::string ft_sensor_reference_frame_
 The sensing reference frame.
 
- Protected Attributes inherited from modulo_controllers::ControllerInterface
std::string hardware_name_
 The hardware name provided by a parameter.
 

Detailed Description

Base controller class that automatically associates joints with a JointState object.

The robot controller interface extends the functionality of the modulo controller interface byautomatically claiming all state interfaces from joints and command interfaces of a given type (position, velocity, effort or acceleration) for those same joints. Joint state and command are associated with these interfaces and abstracted as JointState pointers for derived classes to access. A robot model, Cartesian state and force-torque sensor state are similarly available based on the URDF and state interfaces.

Definition at line 23 of file RobotControllerInterface.hpp.

Constructor & Destructor Documentation

◆ RobotControllerInterface() [1/2]

modulo_controllers::RobotControllerInterface::RobotControllerInterface ( )

Default constructor.

Definition at line 18 of file RobotControllerInterface.cpp.

◆ RobotControllerInterface() [2/2]

modulo_controllers::RobotControllerInterface::RobotControllerInterface ( bool  robot_model_required,
const std::string &  control_type = "",
bool  load_geometries = false 
)
explicit

Constructor with robot model flag and a control type to determine the command interfaces to claim.

Parameters
robot_model_requiredFlag to indicate if a robot model is required for the controller
control_typeOne of [position, velocity, effort or acceleration]
load_geometriesIf true, load the URDF geometries into the robot model for collision features

Definition at line 20 of file RobotControllerInterface.cpp.

Member Function Documentation

◆ add_interfaces()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn modulo_controllers::RobotControllerInterface::add_interfaces ( )
overridevirtual

Add interfaces like parameters, signals, services, and predicates to the controller.

This function is called during the on_init callback of the base class to perform post-construction steps.

Returns
SUCCESS or ERROR

Declare additional parameters.

Reimplemented from modulo_controllers::ControllerInterface.

Definition at line 35 of file RobotControllerInterface.cpp.

◆ compute_cartesian_state()

void modulo_controllers::RobotControllerInterface::compute_cartesian_state ( )
protected

Compute the Cartesian state from forward kinematics of the current joint state.

This should only be used if a robot model has been generated, in which case the forward kinematics is calculated to get pose and twist for the desired target frame.

Definition at line 302 of file RobotControllerInterface.cpp.

◆ get_cartesian_state()

const CartesianState & modulo_controllers::RobotControllerInterface::get_cartesian_state ( )
protected

Access the Cartesian state object.

This internally calls compute_cartesian_state()

Returns
A const reference to the CartesianState object

Definition at line 292 of file RobotControllerInterface.cpp.

◆ get_ft_sensor()

const CartesianWrench & modulo_controllers::RobotControllerInterface::get_ft_sensor ( )
protected

Access the Cartesian wrench object.

Returns
A const reference to the CartesianWrench object

Definition at line 298 of file RobotControllerInterface.cpp.

◆ get_joint_state()

const JointState & modulo_controllers::RobotControllerInterface::get_joint_state ( )
protected

Access the joint state object.

Returns
A const reference to the JointState object

Definition at line 288 of file RobotControllerInterface.cpp.

◆ on_activate()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn modulo_controllers::RobotControllerInterface::on_activate ( )
overridevirtual

Activate the controller.

This method should be overridden by derived classes.

Returns
SUCCESS or ERROR

Initialize a fore torque sensor if applicable

Reimplemented from modulo_controllers::ControllerInterface.

Definition at line 176 of file RobotControllerInterface.cpp.

◆ on_configure()

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn modulo_controllers::RobotControllerInterface::on_configure ( )
overridevirtual

Configure the controller.

This method should be overridden by derived classes.

Returns
SUCCESS or ERROR

Create a robot model from the robot description, get and sort the joints and construct the internal joint state object.

Reimplemented from modulo_controllers::ControllerInterface.

Definition at line 59 of file RobotControllerInterface.cpp.

◆ on_validate_parameter_callback()

bool modulo_controllers::RobotControllerInterface::on_validate_parameter_callback ( const std::shared_ptr< state_representation::ParameterInterface > &  parameter)
overrideprotectedvirtual

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 from modulo_controllers::BaseControllerInterface.

Definition at line 356 of file RobotControllerInterface.cpp.

◆ set_joint_command()

void modulo_controllers::RobotControllerInterface::set_joint_command ( const state_representation::JointState &  joint_command)
protected

Set the joint command object.

Parameters
joint_commandA JointState command object

Definition at line 314 of file RobotControllerInterface.cpp.

Member Data Documentation

◆ ft_sensor_name_

std::string modulo_controllers::RobotControllerInterface::ft_sensor_name_
protected

The name of a force torque sensor in the hardware description.

Definition at line 100 of file RobotControllerInterface.hpp.

◆ ft_sensor_reference_frame_

std::string modulo_controllers::RobotControllerInterface::ft_sensor_reference_frame_
protected

The sensing reference frame.

Definition at line 101 of file RobotControllerInterface.hpp.

◆ robot_

std::shared_ptr<robot_model::Model> modulo_controllers::RobotControllerInterface::robot_
protected

Robot model object generated from URDF.

Definition at line 97 of file RobotControllerInterface.hpp.

◆ task_space_frame_

std::string modulo_controllers::RobotControllerInterface::task_space_frame_
protected

The frame in task space for forward kinematics calculations, if applicable.

Definition at line 98 of file RobotControllerInterface.hpp.


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