ros2_control - rolling
Public Member Functions | List of all members
HardwareInterfaceAdapter< hardware_interface::HW_IF_EFFORT > Class Reference

Adapter for an effort-controlled hardware interface. Maps position and velocity errors to effort commands through a position PID loop. More...

#include <hardware_interface_adapter.hpp>

Public Member Functions

template<typename ParameterT >
auto auto_declare (const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node, const std::string &name, const ParameterT &default_value)
 
bool init (std::optional< std::reference_wrapper< hardware_interface::LoanedCommandInterface >> joint_handle, const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node)
 
void starting (const rclcpp::Time &)
 
void stopping (const rclcpp::Time &)
 
double updateCommand (double, double, double error_position, double error_velocity, double max_allowed_effort)
 

Detailed Description

Adapter for an effort-controlled hardware interface. Maps position and velocity errors to effort commands through a position PID loop.

The following is an example configuration of a controller that uses this adapter. Notice the gains entry:

gripper_controller: type:
"gripper_action_controller/GripperActionController" joints: gripper_joint
goal_tolerance: 0.01
stalled_velocity_threshold: 0.01
stall_timeout: 0.2
gains:
gripper_joint: {p: 200, d: 1, i: 5, i_clamp: 1}

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