Class ChainableControllerInterface
Defined in File chainable_controller_interface.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterfaceBase
(Class ControllerInterfaceBase)
Class Documentation
-
class ChainableControllerInterface : public controller_interface::ControllerInterfaceBase
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.
Public Functions
-
CONTROLLER_INTERFACE_PUBLIC ChainableControllerInterface()
-
virtual CONTROLLER_INTERFACE_PUBLIC ~ChainableControllerInterface() = default
- virtual CONTROLLER_INTERFACE_PUBLIC return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) final
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:
time – [in] The time at the start of this control loop iteration
period – [in] The measured time taken by the last control loop iteration
- Returns:
return_type::OK if update is successfully, otherwise return_type::ERROR.
- virtual CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
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.
- virtual CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterface::ConstSharedPtr > export_state_interfaces () final
Export interfaces for a chainable controller that can be used as state interface by other controllers.
- Returns:
list of state interfaces for preceding controllers.
- virtual CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterface::SharedPtr > export_reference_interfaces () final
Export interfaces for a chainable controller that can be used as command interface of other controllers.
- Returns:
list of command interfaces for preceding controllers.
- virtual CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
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.
- virtual CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
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.
Protected Functions
-
virtual std::vector<hardware_interface::StateInterface> on_export_state_interfaces()
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.
-
virtual std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces()
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.
-
virtual bool on_set_chained_mode(bool chained_mode)
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:
flag – [in] marking 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.
-
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.
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.
-
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.
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.
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_
-
CONTROLLER_INTERFACE_PUBLIC ChainableControllerInterface()