ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
controller_interface::ControllerInterfaceBase Class Referenceabstract

#include <controller_interface_base.hpp>

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

Public Member Functions

virtual InterfaceConfiguration command_interface_configuration () const =0
 Get configuration for controller's required command interfaces.
 
virtual InterfaceConfiguration state_interface_configuration () const =0
 Get configuration for controller's required state interfaces.
 
virtual 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.
 
virtual void release_interfaces ()
 Method that releases the Loaned interfaces from the controller.
 
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)
 
const rclcpp_lifecycle::State & configure ()
 Custom configure method to read additional parameters for controller-nodes.
 
virtual CallbackReturn on_init ()=0
 Extending interface with initialization method which is individual for each controller.
 
virtual return_type update (const rclcpp::Time &time, const rclcpp::Duration &period)=0
 
ControllerUpdateStatus trigger_update (const rclcpp::Time &time, const rclcpp::Duration &period)
 
std::shared_ptr< rclcpp_lifecycle::LifecycleNode > get_node ()
 
std::shared_ptr< const rclcpp_lifecycle::LifecycleNode > get_node () const
 
const rclcpp_lifecycle::State & get_lifecycle_state () const
 
unsigned int get_update_rate () const
 
bool is_async () const
 
const std::string & get_robot_description () const
 
virtual 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.
 
virtual bool is_chainable () const =0
 Get information if a controller is chainable.
 
virtual std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces ()=0
 
virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces ()=0
 
virtual bool set_chained_mode (bool chained_mode)=0
 
virtual bool is_in_chained_mode () const =0
 Get information if a controller is currently in chained mode.
 
void wait_for_trigger_update_to_finish ()
 

Protected Attributes

std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Detailed Description

Base interface class for an controller. The interface may not be used to implement a controller. The class provides definitions for ControllerInterface and ChainableControllerInterface that should be implemented and extended for a specific controller.

Member Function Documentation

◆ assign_interfaces()

void controller_interface::ControllerInterfaceBase::assign_interfaces ( std::vector< hardware_interface::LoanedCommandInterface > &&  command_interfaces,
std::vector< hardware_interface::LoanedStateInterface > &&  state_interfaces 
)
virtual

Method that assigns the Loaned interfaces to the controller.

Method used by the controller_manager to assign the interfaces to the controller.

Note
When this method is overridden, the user has to also implement the release_interfaces method by overriding it to release the interfaces.
Parameters
[in]command_interfacesvector of command interfaces to be assigned to the controller.
[in]state_interfacesvector of state interfaces to be assigned to the controller.

◆ auto_declare()

template<typename ParameterT >
auto controller_interface::ControllerInterfaceBase::auto_declare ( const std::string &  name,
const ParameterT &  default_value 
)
inline

Declare and initialize a parameter with a type.

Wrapper function for templated node's declare_parameter() which checks if parameter is already declared. For use in all components that inherit from ControllerInterfaceBase

◆ command_interface_configuration()

virtual InterfaceConfiguration controller_interface::ControllerInterfaceBase::command_interface_configuration ( ) const
pure virtual

Get configuration for controller's required command interfaces.

Method used by the controller_manager to get the set of command interfaces used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the command_interfaces_ member.

Returns
configuration of command interfaces.

Implemented in ros2_control_demo_example_10::GPIOController, passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gripper_action_controller::GripperActionController< HardwareInterface >, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, mecanum_drive_controller::MecanumDriveController, parallel_gripper_action_controller::GripperActionController, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.

◆ define_custom_node_options()

virtual rclcpp::NodeOptions controller_interface::ControllerInterfaceBase::define_custom_node_options ( ) const
inlinevirtual

Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the controller upon loading the controller.

Note
The controller_manager will modify these NodeOptions in case a params file is passed by the spawner to load the controller parameters or when controllers are loaded in simulation (see ros2_control#1311, ros2_controllers#698 , ros2_controllers#795,ros2_controllers#966 for more details)
Returns
NodeOptions required for the configuration of the controller lifecycle node

◆ export_reference_interfaces()

virtual std::vector< hardware_interface::CommandInterface::SharedPtr > controller_interface::ControllerInterfaceBase::export_reference_interfaces ( )
pure virtual

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

Returns
list of command interfaces for preceding controllers.

Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.

◆ export_state_interfaces()

virtual std::vector< hardware_interface::StateInterface::ConstSharedPtr > controller_interface::ControllerInterfaceBase::export_state_interfaces ( )
pure virtual

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

Returns
list of state interfaces for preceding controllers.

Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.

◆ is_chainable()

virtual bool controller_interface::ControllerInterfaceBase::is_chainable ( ) const
pure virtual

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.

Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.

◆ is_in_chained_mode()

virtual bool controller_interface::ControllerInterfaceBase::is_in_chained_mode ( ) const
pure virtual

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.

Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.

◆ on_init()

virtual CallbackReturn controller_interface::ControllerInterfaceBase::on_init ( )
pure virtual

◆ release_interfaces()

void controller_interface::ControllerInterfaceBase::release_interfaces ( )
virtual

Method that releases the Loaned interfaces from the controller.

Method used by the controller_manager to release the interfaces from the controller.

◆ set_chained_mode()

virtual bool controller_interface::ControllerInterfaceBase::set_chained_mode ( bool  chained_mode)
pure virtual

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.

Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.

◆ state_interface_configuration()

virtual InterfaceConfiguration controller_interface::ControllerInterfaceBase::state_interface_configuration ( ) const
pure virtual

Get configuration for controller's required state interfaces.

Method used by the controller_manager to get the set of state interface used by the controller. Each controller can use individual method to determine interface names that in simples case have the following format: <joint>/<interface>. The method is called only in inactive or active state, i.e., on_configure has to be called first. The configuration is used to check if controller can be activated and to claim interfaces from hardware. The claimed interfaces are populated in the state_interfaces_ member.

Returns
configuration of state interfaces.

Implemented in ros2_control_demo_example_10::GPIOController, passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gripper_action_controller::GripperActionController< HardwareInterface >, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, mecanum_drive_controller::MecanumDriveController, parallel_gripper_action_controller::GripperActionController, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.

◆ trigger_update()

ControllerUpdateStatus controller_interface::ControllerInterfaceBase::trigger_update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)

Trigger update method. This method is used by the controller_manager to trigger the update method of the controller. The method is used to trigger the update method of the controller synchronously or asynchronously, based on the controller configuration. 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
ControllerUpdateStatus. The status contains information if the update was triggered successfully, the result of the update method and the execution duration of the update method.

◆ update()

virtual return_type controller_interface::ControllerInterfaceBase::update ( const rclcpp::Time &  time,
const rclcpp::Duration &  period 
)
pure virtual

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 since the last control loop iteration
Returns
return_type::OK if update is successfully, otherwise return_type::ERROR.

Implemented in controller_interface::ChainableControllerInterface, ros2_control_demo_example_10::GPIOController, ros2_control_demo_example_7::RobotController, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gripper_action_controller::GripperActionController< HardwareInterface >, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, parallel_gripper_action_controller::GripperActionController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, and tricycle_controller::TricycleController.

◆ wait_for_trigger_update_to_finish()

void controller_interface::ControllerInterfaceBase::wait_for_trigger_update_to_finish ( )

Method to wait for any running async update cycle to finish after finishing the current cycle. This is needed to be called before deactivating the controller by the controller_manager, so that the interfaces still exist when the controller finishes its cycle and then it's exits.

Note
The method is not real-time safe and shouldn't be called in the control loop.

If the controller is running in async mode, the method will wait for the current async update to finish. If the controller is not running in async mode, the method will do nothing.


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