ros2_control - rolling
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
controller_interface::ChainableControllerInterface Class Referenceabstract

#include <chainable_controller_interface.hpp>

Inheritance diagram for controller_interface::ChainableControllerInterface:
Inheritance graph
[legend]
Collaboration diagram for controller_interface::ChainableControllerInterface:
Collaboration graph
[legend]

Public Member Functions

CONTROLLER_INTERFACE_PUBLIC return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 Get information if a controller is chainable. More...
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 Get information if a controller is currently in chained mode. More...
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration command_interface_configuration () const =0
 Get configuration for controller's required command interfaces. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration state_interface_configuration () const =0
 Get configuration for controller's required state interfaces. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC void assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces)
 Method that assigns the Loaned interfaces to the controller. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC void release_interfaces ()
 Method that releases the Loaned interfaces from the controller. More...
 
CONTROLLER_INTERFACE_PUBLIC return_type init (const std::string &controller_name, const std::string &urdf, unsigned int cm_update_rate, const std::string &node_namespace, const rclcpp::NodeOptions &node_options)
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
virtual CONTROLLER_INTERFACE_PUBLIC CallbackReturn on_init ()=0
 Extending interface with initialization method which is individual for each controller.
 
CONTROLLER_INTERFACE_PUBLIC ControllerUpdateStatus trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period)
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & get_lifecycle_state () const
 
CONTROLLER_INTERFACE_PUBLIC unsigned int get_update_rate () const
 
CONTROLLER_INTERFACE_PUBLIC bool is_async () const
 
CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description () const
 
virtual CONTROLLER_INTERFACE_PUBLIC rclcpp::NodeOptions define_custom_node_options () const
 
template<typename ParameterT >
auto auto_declare (const std::string &name, const ParameterT &default_value)
 Declare and initialize a parameter with a type. More...
 
CONTROLLER_INTERFACE_PUBLIC void wait_for_trigger_update_to_finish ()
 

Protected Member Functions

virtual std::vector< hardware_interface::StateInterfaceon_export_state_interfaces ()
 
virtual std::vector< hardware_interface::CommandInterfaceon_export_reference_interfaces ()
 
virtual bool on_set_chained_mode (bool chained_mode)
 Virtual method that each chainable controller should implement to switch chained mode. More...
 
virtual return_type update_reference_from_subscribers (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Update reference from input topics when not in chained mode. More...
 
virtual return_type update_and_write_commands (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 Execute calculations of the controller and update command interfaces. More...
 

Protected Attributes

std::vector< std::string > exported_state_interface_names_
 Storage of values for state interfaces.
 
std::vector< hardware_interface::StateInterface::SharedPtr > ordered_exported_state_interfaces_
 
std::unordered_map< std::string, hardware_interface::StateInterface::SharedPtr > exported_state_interfaces_
 
std::vector< double > state_interfaces_values_
 
std::vector< std::string > exported_reference_interface_names_
 Storage of values for reference interfaces.
 
std::vector< double > reference_interfaces_
 
std::vector< hardware_interface::CommandInterface::SharedPtr > ordered_exported_reference_interfaces_
 
std::unordered_map< std::string, hardware_interface::CommandInterface::SharedPtr > exported_reference_interfaces_
 
- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Detailed Description

Virtual class to implement when integrating a controller that can be preceded by other controllers. Specialization of ControllerInterface class to force implementation of methods specific for "chainable" controller, i.e., controller that can be preceded by an another controller, for example inner controller of an control cascade.

Member Function Documentation

◆ export_reference_interfaces()

std::vector< hardware_interface::CommandInterface::SharedPtr > controller_interface::ChainableControllerInterface::export_reference_interfaces ( )
finalvirtual

Export interfaces for a chainable controller that can be used as command interface of other controllers.

Returns
list of command interfaces for preceding controllers.

Implements controller_interface::ControllerInterfaceBase.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface::ConstSharedPtr > controller_interface::ChainableControllerInterface::export_state_interfaces ( )
finalvirtual

Export interfaces for a chainable controller that can be used as state interface by other controllers.

Returns
list of state interfaces for preceding controllers.

Implements controller_interface::ControllerInterfaceBase.

◆ is_chainable()

bool controller_interface::ChainableControllerInterface::is_chainable ( ) const
finalvirtual

Get information if a controller is chainable.

Get information if a controller is chainable.

Returns
true is controller is chainable and false if it is not.

Implements controller_interface::ControllerInterfaceBase.

◆ is_in_chained_mode()

bool controller_interface::ChainableControllerInterface::is_in_chained_mode ( ) const
finalvirtual

Get information if a controller is currently in chained mode.

Get information about controller if it is currently used in chained mode. In chained mode only internal interfaces are available and all subscribers are expected to be disabled. This prevents concurrent writing to controller's inputs from multiple sources.

Returns
true is controller is in chained mode and false if it is not.

Implements controller_interface::ControllerInterfaceBase.

◆ on_export_reference_interfaces()

std::vector< hardware_interface::CommandInterface > controller_interface::ChainableControllerInterface::on_export_reference_interfaces ( )
protectedvirtual

Virtual method that each chainable controller should implement to export its read/write chainable interfaces. Each chainable controller implements this methods where all input (command) interfaces are exported. The method has the same meaning as export_command_interface method from hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.

Returns
list of CommandInterfaces that other controller can use as their outputs.

Reimplemented in steering_controllers_library::SteeringControllersLibrary, pid_controller::PidController, mecanum_drive_controller::MecanumDriveController, admittance_controller::AdmittanceController, and passthrough_controller::PassthroughController.

◆ on_export_state_interfaces()

std::vector< hardware_interface::StateInterface > controller_interface::ChainableControllerInterface::on_export_state_interfaces ( )
protectedvirtual

Virtual method that each chainable controller should implement to export its read-only chainable interfaces. Each chainable controller implements this methods where all its state(read only) interfaces are exported. The method has the same meaning as export_state_interfaces method from hardware_interface::SystemInterface or hardware_interface::ActuatorInterface.

Returns
list of StateInterfaces that other controller can use as their inputs.

Reimplemented in pid_controller::PidController, and force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster.

◆ on_set_chained_mode()

bool controller_interface::ChainableControllerInterface::on_set_chained_mode ( bool  chained_mode)
protectedvirtual

Virtual method that each chainable controller should implement to switch chained mode.

Each chainable controller implements this methods to switch between "chained" and "external" mode. In "chained" mode all external interfaces like subscriber and service servers are disabled to avoid potential concurrency in input commands.

Parameters
[in]flagmarking a switch to or from chained mode.
Returns
true if controller successfully switched between "chained" and "external" mode. \default returns true so the method don't have to be overridden if controller can always switch chained mode.

Reimplemented in steering_controllers_library::SteeringControllersLibrary, pid_controller::PidController, mecanum_drive_controller::MecanumDriveController, and passthrough_controller::PassthroughController.

◆ set_chained_mode()

bool controller_interface::ChainableControllerInterface::set_chained_mode ( bool  chained_mode)
finalvirtual

Set chained mode of a chainable controller. This method triggers internal processes to switch a chainable controller to "chained" mode and vice-versa. Setting controller to "chained" mode usually involves the usage of the controller's reference interfaces by the other controllers

Returns
true if mode is switched successfully and false if not.

Implements controller_interface::ControllerInterfaceBase.

◆ update()

return_type controller_interface::ChainableControllerInterface::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
finalvirtual

Control step update. Command interfaces are updated based on on reference inputs and current states. The method called in the (real-time) control loop.

Parameters
[in]timeThe time at the start of this control loop iteration
[in]periodThe measured time taken by the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implements controller_interface::ControllerInterfaceBase.

◆ update_and_write_commands()

virtual return_type controller_interface::ChainableControllerInterface::update_and_write_commands ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
protectedpure virtual

Execute calculations of the controller and update command interfaces.

Update method for chainable controllers. In this method is valid to assume that \reference_interfaces_ hold the values for calculation of the commands in the current control step. This means that this method is called after \update_reference_from_subscribers if controller is not in chained mode.

Returns
return_type::OK if calculation and writing of interface is successfully, otherwise return_type::ERROR.

Implemented in steering_controllers_library::SteeringControllersLibrary, pid_controller::PidController, mecanum_drive_controller::MecanumDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, admittance_controller::AdmittanceController, and passthrough_controller::PassthroughController.

◆ update_reference_from_subscribers()

virtual return_type controller_interface::ChainableControllerInterface::update_reference_from_subscribers ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
protectedpure virtual

Update reference from input topics when not in chained mode.

Each chainable controller implements this method to update reference from subscribers when not in chained mode.

Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implemented in steering_controllers_library::SteeringControllersLibrary, pid_controller::PidController, mecanum_drive_controller::MecanumDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, admittance_controller::AdmittanceController, and passthrough_controller::PassthroughController.


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