ros2_control - rolling
Public Member Functions | List of all members
controller_interface::ControllerInterface Class Reference
Inheritance diagram for controller_interface::ControllerInterface:
Inheritance graph
[legend]
Collaboration diagram for controller_interface::ControllerInterface:
Collaboration graph
[legend]

Public Member Functions

CONTROLLER_INTERFACE_PUBLIC bool is_chainable () const final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::StateInterfaceexport_state_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC std::vector< hardware_interface::CommandInterfaceexport_reference_interfaces () final
 
CONTROLLER_INTERFACE_PUBLIC bool set_chained_mode (bool chained_mode) final
 
CONTROLLER_INTERFACE_PUBLIC bool is_in_chained_mode () const final
 
- Public Member Functions inherited from controller_interface::ControllerInterfaceBase
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration command_interface_configuration () const =0
 Get configuration for controller's required command interfaces. More...
 
virtual CONTROLLER_INTERFACE_PUBLIC InterfaceConfiguration state_interface_configuration () const =0
 Get configuration for controller's required state interfaces. More...
 
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 ()
 
CONTROLLER_INTERFACE_PUBLIC 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)
 
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< const 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
 
CONTROLLER_INTERFACE_PUBLIC bool is_async () const
 
CONTROLLER_INTERFACE_PUBLIC const std::string & get_robot_description () const
 
virtual CONTROLLER_INTERFACE_PUBLIC 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. More...
 

Additional Inherited Members

- Protected Attributes inherited from controller_interface::ControllerInterfaceBase
std::vector< hardware_interface::LoanedCommandInterfacecommand_interfaces_
 
std::vector< hardware_interface::LoanedStateInterfacestate_interfaces_
 

Member Function Documentation

◆ export_reference_interfaces()

std::vector< hardware_interface::CommandInterface > controller_interface::ControllerInterface::export_reference_interfaces ( )
finalvirtual

Controller has no reference interfaces.

Returns
empty list.

Implements controller_interface::ControllerInterfaceBase.

◆ export_state_interfaces()

std::vector< hardware_interface::StateInterface > controller_interface::ControllerInterface::export_state_interfaces ( )
finalvirtual

A non-chainable controller doesn't export any state interfaces.

Returns
empty list.

Implements controller_interface::ControllerInterfaceBase.

◆ is_chainable()

bool controller_interface::ControllerInterface::is_chainable ( ) const
finalvirtual

Controller is not chainable.

Returns
false.

Implements controller_interface::ControllerInterfaceBase.

◆ is_in_chained_mode()

bool controller_interface::ControllerInterface::is_in_chained_mode ( ) const
finalvirtual

Controller can not be in chained mode.

Returns
false.

Implements controller_interface::ControllerInterfaceBase.

◆ set_chained_mode()

bool controller_interface::ControllerInterface::set_chained_mode ( bool  chained_mode)
finalvirtual

Controller is not chainable, therefore no chained mode can be set.

Returns
false.

Implements controller_interface::ControllerInterfaceBase.


The documentation for this class was generated from the following files: