Public Member Functions | Private Types | Private Attributes | List of all members
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface > Class Template 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.h>

Public Member Functions

 HardwareInterfaceAdapter ()
 
bool init (hardware_interface::JointHandle &joint_handle, ros::NodeHandle &controller_nh)
 
void starting (const ros::Time &time)
 
void stopping (const ros::Time &time)
 
double updateCommand (const ros::Time &, const ros::Duration &period, double desired_position, double desired_velocity, double error_position, double error_velocity, double max_allowed_effort)
 

Private Types

typedef boost::shared_ptr< control_toolbox::PidPidPtr
 

Private Attributes

hardware_interface::JointHandlejoint_handle_ptr_
 
PidPtr pid_
 

Detailed Description

template<>
class HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >

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}

Definition at line 129 of file hardware_interface_adapter.h.

Member Typedef Documentation

Definition at line 185 of file hardware_interface_adapter.h.

Constructor & Destructor Documentation

Definition at line 132 of file hardware_interface_adapter.h.

Member Function Documentation

Definition at line 134 of file hardware_interface_adapter.h.

Definition at line 153 of file hardware_interface_adapter.h.

Definition at line 164 of file hardware_interface_adapter.h.

double HardwareInterfaceAdapter< hardware_interface::EffortJointInterface >::updateCommand ( const ros::Time ,
const ros::Duration period,
double  desired_position,
double  desired_velocity,
double  error_position,
double  error_velocity,
double  max_allowed_effort 
)
inline

Definition at line 166 of file hardware_interface_adapter.h.

Member Data Documentation

Definition at line 187 of file hardware_interface_adapter.h.

Definition at line 186 of file hardware_interface_adapter.h.


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


gripper_action_controller
Author(s): Sachin Chitta
autogenerated on Thu Apr 11 2019 03:08:30