|  | ros2_control - rolling
    | 
#include <controller_interface_base.hpp>


| 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) | 
| return_type | init (const controller_interface::ControllerInterfaceParams ¶ms) | 
| 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 | 
| const std::unordered_map< std::string, joint_limits::JointLimits > & | get_hard_joint_limits () const | 
| const std::unordered_map< std::string, joint_limits::SoftJointLimits > & | get_soft_joint_limits () 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 () | 
| void | prepare_for_deactivation () | 
| std::string | get_name () const | 
| void | enable_introspection (bool enable) | 
| Enable or disable introspection of the controller. | |
| Protected Attributes | |
| std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ | 
| std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ | 
| pal_statistics::RegistrationsRAII | stats_registrations_ | 
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. 
| 
 | virtual | 
Method that assigns the Loaned interfaces to the controller.
Method used by the controller_manager to assign the interfaces to the controller.
release_interfaces method by overriding it to release the interfaces.| [in] | command_interfaces | vector of command interfaces to be assigned to the controller. | 
| [in] | state_interfaces | vector of state interfaces to be assigned to the controller. | 
| 
 | 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
| 
 | 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.
Implemented in passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, chained_filter_controller::ChainedFilter, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gps_sensor_broadcaster::GPSSensorBroadcaster, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, mecanum_drive_controller::MecanumDriveController, motion_primitives_controllers::MotionPrimitivesBaseController, omni_wheel_drive_controller::OmniWheelDriveController, parallel_gripper_action_controller::GripperActionController, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.
| 
 | inlinevirtual | 
Method used by the controller_manager for base NodeOptions to instantiate the Lifecycle node of the controller upon loading the controller.
| void controller_interface::ControllerInterfaceBase::enable_introspection | ( | bool | enable | ) | 
Enable or disable introspection of the controller.
| [in] | enable | Enable introspection if true, disable otherwise. | 
| 
 | pure virtual | 
Export interfaces for a chainable controller that can be used as command interface of other controllers.
Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.
| 
 | pure virtual | 
Export interfaces for a chainable controller that can be used as state interface by other controllers.
Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.
| const std::unordered_map< std::string, joint_limits::JointLimits > & controller_interface::ControllerInterfaceBase::get_hard_joint_limits | ( | ) | const | 
Get the unordered map of joint limits that are defined in the robot description.
| const std::unordered_map< std::string, joint_limits::SoftJointLimits > & controller_interface::ControllerInterfaceBase::get_soft_joint_limits | ( | ) | const | 
Get the unordered map of soft joint limits that are defined in the robot description.
| 
 | pure virtual | 
Get information if a controller is chainable.
Get information if a controller is chainable.
Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.
| 
 | 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.
Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.
| 
 | pure virtual | 
Extending interface with initialization method which is individual for each controller.
Implemented in passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, chained_filter_controller::ChainedFilter, diff_drive_controller::DiffDriveController, effort_controllers::JointGroupEffortController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gps_sensor_broadcaster::GPSSensorBroadcaster, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, mecanum_drive_controller::MecanumDriveController, motion_primitives_controllers::MotionPrimitivesBaseController, motion_primitives_controllers::MotionPrimitivesForwardController, omni_wheel_drive_controller::OmniWheelDriveController, parallel_gripper_action_controller::GripperActionController, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, position_controllers::JointGroupPositionController, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, tricycle_controller::TricycleController, and velocity_controllers::JointGroupVelocityController.
| void controller_interface::ControllerInterfaceBase::prepare_for_deactivation | ( | ) | 
Method to prepare the controller for deactivation. This method is called by the controller manager before deactivating the controller. The method is used to prepare the controller for deactivation, e.g., to stop triggering the update cycles further. This method is especially needed for controllers running in async mode and different frequency than the control manager.
If the controller is running in async mode, the method will stop the async update cycles. If the controller is not running in async mode, the method will do nothing.
| 
 | virtual | 
Method that releases the Loaned interfaces from the controller.
Method used by the controller_manager to release the interfaces from the controller.
| 
 | 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
Implemented in controller_interface::ChainableControllerInterface, and controller_interface::ControllerInterface.
| 
 | 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.
Implemented in passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, chained_filter_controller::ChainedFilter, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, gps_sensor_broadcaster::GPSSensorBroadcaster, imu_sensor_broadcaster::IMUSensorBroadcaster, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, mecanum_drive_controller::MecanumDriveController, motion_primitives_controllers::MotionPrimitivesBaseController, omni_wheel_drive_controller::OmniWheelDriveController, parallel_gripper_action_controller::GripperActionController, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.
| 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.
| [in] | time | The time at the start of this control loop iteration | 
| [in] | period | The measured time taken by the last control loop iteration | 
| 
 | 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.
| [in] | time | The time at the start of this control loop iteration | 
| [in] | period | The measured time since the last control loop iteration | 
Implemented in gps_sensor_broadcaster::GPSSensorBroadcaster, controller_interface::ChainableControllerInterface, ros2_control_demo_example_7::RobotController, forward_command_controller::ForwardControllersBase, gpio_controllers::GpioCommandController, joint_state_broadcaster::JointStateBroadcaster, joint_trajectory_controller::JointTrajectoryController, motion_primitives_controllers::MotionPrimitivesBaseController, motion_primitives_controllers::MotionPrimitivesForwardController, parallel_gripper_action_controller::GripperActionController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, and tricycle_controller::TricycleController.
| 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.
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.
| 
 | protected | 
Loaned command interfaces.
| 
 | protected | 
Loaned state interfaces.