Class ControllerInterfaceBase
Defined in File controller_interface_base.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Derived Types
public controller_interface::ChainableControllerInterface
(Class ChainableControllerInterface)public controller_interface::ControllerInterface
(Class ControllerInterface)
Class Documentation
-
class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Base interface class for an controller. The interface may not be used to implement a controller. The class provides definitions for
ControllerInterface
andChainableControllerInterface
that should be implemented and extended for a specific controller.Subclassed by controller_interface::ChainableControllerInterface, controller_interface::ControllerInterface
Public Functions
-
CONTROLLER_INTERFACE_PUBLIC ControllerInterfaceBase() = default
-
virtual CONTROLLER_INTERFACE_PUBLIC ~ControllerInterfaceBase() = default
- virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration command_interface_configuration () const =0
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 ininactive
oractive
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.
- virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration state_interface_configuration () const =0
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 ininactive
oractive
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.- Returns:
configuration of 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
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.
- 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>
inline auto auto_declare(const std::string &name, const ParameterT &default_value) 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
- virtual CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const =0
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::CommandInterface > export_reference_interfaces ()=0
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)=0
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.
- Returns:
true if mode is switched successfully and false if not.
- virtual CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const =0
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 Attributes
-
std::vector<hardware_interface::LoanedCommandInterface> command_interfaces_
-
std::vector<hardware_interface::LoanedStateInterface> state_interfaces_
-
unsigned int update_rate_ = 0
-
CONTROLLER_INTERFACE_PUBLIC ControllerInterfaceBase() = default