Public Member Functions | Private Types | Private Attributes | List of all members
ClosedLoopHardwareInterfaceAdapter< State > Class Template Reference

Helper base class template for closed loop HardwareInterfaceAdapter implementations. More...

#include <hardware_interface_adapter.h>

Inheritance diagram for ClosedLoopHardwareInterfaceAdapter< State >:
Inheritance graph
[legend]

Public Member Functions

 ClosedLoopHardwareInterfaceAdapter ()
 
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 &desired_state, const State &state_error)
 

Private Types

typedef boost::shared_ptr< control_toolbox::PidPidPtr
 

Private Attributes

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

Detailed Description

template<class State>
class ClosedLoopHardwareInterfaceAdapter< State >

Helper base class template for closed loop HardwareInterfaceAdapter implementations.

Adapters leveraging (specializing) this class will generate a command given the desired state and state error using a velocity feedforward term plus a corrective PID term.

Use one of the available template specializations of this class (or create your own) to adapt the JointTrajectoryController to a specidfic hardware interface.

Definition at line 145 of file hardware_interface_adapter.h.

Member Typedef Documentation

template<class State >
typedef boost::shared_ptr<control_toolbox::Pid> ClosedLoopHardwareInterfaceAdapter< State >::PidPtr
private

Definition at line 217 of file hardware_interface_adapter.h.

Constructor & Destructor Documentation

template<class State >
ClosedLoopHardwareInterfaceAdapter< State >::ClosedLoopHardwareInterfaceAdapter ( )
inline

Definition at line 148 of file hardware_interface_adapter.h.

Member Function Documentation

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

Definition at line 150 of file hardware_interface_adapter.h.

template<class State >
void ClosedLoopHardwareInterfaceAdapter< State >::starting ( const ros::Time )
inline

Definition at line 181 of file hardware_interface_adapter.h.

template<class State >
void ClosedLoopHardwareInterfaceAdapter< State >::stopping ( const ros::Time )
inline

Definition at line 193 of file hardware_interface_adapter.h.

template<class State >
void ClosedLoopHardwareInterfaceAdapter< State >::updateCommand ( const ros::Time ,
const ros::Duration period,
const State &  desired_state,
const State &  state_error 
)
inline

Definition at line 195 of file hardware_interface_adapter.h.

Member Data Documentation

template<class State >
std::vector<hardware_interface::JointHandle>* ClosedLoopHardwareInterfaceAdapter< State >::joint_handles_ptr_
private

Definition at line 222 of file hardware_interface_adapter.h.

template<class State >
std::vector<PidPtr> ClosedLoopHardwareInterfaceAdapter< State >::pids_
private

Definition at line 218 of file hardware_interface_adapter.h.

template<class State >
std::vector<double> ClosedLoopHardwareInterfaceAdapter< State >::velocity_ff_
private

Definition at line 220 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 Apr 18 2020 03:58:18