ros2_control - rolling
|
#include <chainable_controller_interface.hpp>
Public Member Functions | |
return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) final |
bool | is_chainable () const final |
Get information if a controller is chainable. | |
std::vector< hardware_interface::StateInterface::ConstSharedPtr > | export_state_interfaces () final |
std::vector< hardware_interface::CommandInterface::SharedPtr > | export_reference_interfaces () final |
bool | set_chained_mode (bool chained_mode) final |
bool | is_in_chained_mode () const final |
Get information if a controller is currently in chained mode. | |
Public Member Functions inherited from controller_interface::ControllerInterfaceBase | |
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. | |
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. | |
void | wait_for_trigger_update_to_finish () |
Protected Member Functions | |
virtual std::vector< hardware_interface::StateInterface > | on_export_state_interfaces () |
virtual std::vector< hardware_interface::CommandInterface > | on_export_reference_interfaces () |
virtual bool | on_set_chained_mode (bool chained_mode) |
Virtual method that each chainable controller should implement to switch chained mode. | |
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. | |
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. | |
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::LoanedCommandInterface > | command_interfaces_ |
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
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.
|
finalvirtual |
Export interfaces for a chainable controller that can be used as command interface of other controllers.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
Export interfaces for a chainable controller that can be used as state interface by other controllers.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
Get information if a controller is chainable.
Get information if a controller is chainable.
Implements controller_interface::ControllerInterfaceBase.
|
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.
Implements controller_interface::ControllerInterfaceBase.
|
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.
Reimplemented in passthrough_controller::PassthroughController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, mecanum_drive_controller::MecanumDriveController, pid_controller::PidController, and steering_controllers_library::SteeringControllersLibrary.
|
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.
Reimplemented in force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, and pid_controller::PidController.
|
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.
[in] | flag | marking a switch to or from chained mode. |
Reimplemented in passthrough_controller::PassthroughController, diff_drive_controller::DiffDriveController, mecanum_drive_controller::MecanumDriveController, pid_controller::PidController, and steering_controllers_library::SteeringControllersLibrary.
|
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
Implements controller_interface::ControllerInterfaceBase.
|
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.
[in] | time | The time at the start of this control loop iteration |
[in] | period | The measured time taken by the last control loop iteration |
Implements controller_interface::ControllerInterfaceBase.
|
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.
Implemented in passthrough_controller::PassthroughController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, mecanum_drive_controller::MecanumDriveController, pid_controller::PidController, and steering_controllers_library::SteeringControllersLibrary.
|
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.
Implemented in passthrough_controller::PassthroughController, admittance_controller::AdmittanceController, diff_drive_controller::DiffDriveController, force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster, mecanum_drive_controller::MecanumDriveController, pid_controller::PidController, and steering_controllers_library::SteeringControllersLibrary.