ros2_control - humble
|
#include <controller_interface_base.hpp>
Public Member Functions | |
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration | command_interface_configuration () const =0 |
Get configuration for controller's required command interfaces. | |
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration | state_interface_configuration () const =0 |
Get configuration for controller's required state interfaces. | |
CONTROLLER_INTERFACE_PUBLIC void | assign_interfaces (std::vector< hardware_interface::LoanedCommandInterface > &&command_interfaces, std::vector< hardware_interface::LoanedStateInterface > &&state_interfaces) |
CONTROLLER_INTERFACE_PUBLIC void | release_interfaces () |
virtual CONTROLLER_INTERFACE_PUBLIC return_type | init (const std::string &controller_name, const std::string &namespace_="", const rclcpp::NodeOptions &node_options=rclcpp::NodeOptions() .allow_undeclared_parameters(true) .automatically_declare_parameters_from_overrides(true)) |
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. | |
virtual CONTROLLER_INTERFACE_PUBLIC return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () |
CONTROLLER_INTERFACE_PUBLIC std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () const |
CONTROLLER_INTERFACE_PUBLIC const rclcpp_lifecycle::State & | get_state () const |
CONTROLLER_INTERFACE_PUBLIC unsigned int | get_update_rate () const |
template<typename ParameterT > | |
auto | auto_declare (const std::string &name, const ParameterT &default_value) |
Declare and initialize a parameter with a type. | |
virtual CONTROLLER_INTERFACE_PUBLIC bool | is_chainable () const =0 |
Get information if a controller is chainable. | |
virtual CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface > | export_reference_interfaces ()=0 |
virtual CONTROLLER_INTERFACE_PUBLIC bool | set_chained_mode (bool chained_mode)=0 |
virtual CONTROLLER_INTERFACE_PUBLIC bool | is_in_chained_mode () const =0 |
Get information if a controller is currently in chained mode. | |
Protected Attributes | |
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
unsigned int | update_rate_ = 0 |
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.
|
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 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, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.
|
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 |
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 ros2_control_demo_example_10::GPIOController, passthrough_controller::PassthroughController, ros2_control_demo_example_7::RobotController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, effort_controllers::JointGroupEffortController, 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, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, position_controllers::JointGroupPositionController, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, tricycle_controller::TricycleController, and velocity_controllers::JointGroupVelocityController.
|
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 disabling of subscribers and other external interfaces to avoid potential concurrency in input commands.
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_interface_ member.
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, pid_controller::PidController, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, steering_controllers_library::SteeringControllersLibrary, and tricycle_controller::TricycleController.
|
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 taken by the last control loop iteration |
Implemented in controller_interface::ChainableControllerInterface, ros2_control_demo_example_10::GPIOController, ros2_control_demo_example_7::RobotController, 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, pose_broadcaster::PoseBroadcaster, range_sensor_broadcaster::RangeSensorBroadcaster, and tricycle_controller::TricycleController.