ros2_control - rolling
|
Public Member Functions | |
bool | is_chainable () const final |
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 |
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. | |
virtual return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period)=0 |
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 () |
Additional Inherited Members | |
Protected Attributes inherited from controller_interface::ControllerInterfaceBase | |
std::vector< hardware_interface::LoanedCommandInterface > | command_interfaces_ |
std::vector< hardware_interface::LoanedStateInterface > | state_interfaces_ |
|
finalvirtual |
Controller has no reference interfaces.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
A non-chainable controller doesn't export any state interfaces.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
Controller is not chainable.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
Controller can not be in chained mode.
Implements controller_interface::ControllerInterfaceBase.
|
finalvirtual |
Controller is not chainable, therefore no chained mode can be set.
Implements controller_interface::ControllerInterfaceBase.