Public Member Functions | Private Types | Private Attributes
HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State > 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>

List of all members.

Public Member Functions

 HardwareInterfaceAdapter ()
bool init (std::vector< hardware_interface::JointHandle > &joint_handles, ros::NodeHandle &controller_nh)
void starting (const ros::Time &)
void stopping (const ros::Time &)
void updateCommand (const ros::Time &, const ros::Duration &period, const State &, const State &state_error)

Private Types

typedef boost::shared_ptr
< control_toolbox::Pid
PidPtr

Private Attributes

std::vector
< hardware_interface::JointHandle > * 
joint_handles_ptr_
std::vector< PidPtrpids_

Detailed Description

template<class State>
class HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >

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:

 head_controller:
   type: "effort_controllers/JointTrajectoryController"
   joints:
     - head_1_joint
     - head_2_joint
   gains:
     head_1_joint: {p: 200, d: 1, i: 5, i_clamp: 1}
     head_2_joint: {p: 200, d: 1, i: 5, i_clamp: 1}
   constraints:
     goal_time: 0.6
     stopped_velocity_tolerance: 0.02
     head_1_joint: {trajectory: 0.05, goal: 0.02}
     head_2_joint: {trajectory: 0.05, goal: 0.02}
   stop_trajectory_duration: 0.5
   state_publish_rate:  25

Definition at line 252 of file hardware_interface_adapter.h.


Member Typedef Documentation

template<class State >
typedef boost::shared_ptr<control_toolbox::Pid> HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::PidPtr [private]

Definition at line 316 of file hardware_interface_adapter.h.


Constructor & Destructor Documentation

Definition at line 255 of file hardware_interface_adapter.h.


Member Function Documentation

template<class State >
bool HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::init ( std::vector< hardware_interface::JointHandle > &  joint_handles,
ros::NodeHandle controller_nh 
) [inline]

Definition at line 257 of file hardware_interface_adapter.h.

template<class State >
void HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::starting ( const ros::Time ) [inline]

Definition at line 281 of file hardware_interface_adapter.h.

template<class State >
void HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::stopping ( const ros::Time ) [inline]

Definition at line 293 of file hardware_interface_adapter.h.

template<class State >
void HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::updateCommand ( const ros::Time ,
const ros::Duration period,
const State &  ,
const State &  state_error 
) [inline]

Definition at line 295 of file hardware_interface_adapter.h.


Member Data Documentation

Definition at line 319 of file hardware_interface_adapter.h.

template<class State >
std::vector<PidPtr> HardwareInterfaceAdapter< hardware_interface::EffortJointInterface, State >::pids_ [private]

Definition at line 317 of file hardware_interface_adapter.h.


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


joint_trajectory_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Aug 13 2016 04:20:51