Template Class HardwareInterfaceAdapter< hardware_interface::HW_IF_EFFORT >

Class Documentation

template<>
class HardwareInterfaceAdapter<hardware_interface::HW_IF_EFFORT>

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}

Public Functions

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