|
controller_interface::InterfaceConfiguration | command_interface_configuration () const override |
| Get configuration for controller's required command interfaces.
|
|
controller_interface::InterfaceConfiguration | state_interface_configuration () const override |
| Get configuration for controller's required state interfaces.
|
|
controller_interface::return_type | update (const rclcpp::Time &time, const rclcpp::Duration &period) override |
|
CallbackReturn | on_init () override |
| Extending interface with initialization method which is individual for each controller.
|
|
CallbackReturn | on_configure (const rclcpp_lifecycle::State &previous_state) override |
|
CallbackReturn | on_activate (const rclcpp_lifecycle::State &previous_state) override |
|
CallbackReturn | on_deactivate (const rclcpp_lifecycle::State &previous_state) override |
|
CallbackReturn | on_cleanup (const rclcpp_lifecycle::State &previous_state) override |
|
CallbackReturn | on_error (const rclcpp_lifecycle::State &previous_state) override |
|
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 |
|
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.
|
|
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 () |
|
|
CallbackReturn | get_traction (const std::string &traction_joint_name, std::vector< TractionHandle > &joint) |
|
CallbackReturn | get_steering (const std::string &steering_joint_name, std::vector< SteeringHandle > &joint) |
|
double | convert_trans_rot_vel_to_steering_angle (double v, double omega, double wheelbase) |
|
std::tuple< double, double > | twist_to_ackermann (double linear_command, double angular_command) |
|
void | reset_odometry (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::Empty::Request > req, std::shared_ptr< std_srvs::srv::Empty::Response > res) |
|
bool | reset () |
|
void | halt () |
|
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 in inactive
or active
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.
Implements controller_interface::ControllerInterfaceBase.
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 in inactive
or active
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_interfaces_ member.
- Returns
- configuration of state interfaces.
Implements controller_interface::ControllerInterfaceBase.