Public Member Functions | Private Attributes | List of all members
HardwareInterfaceAdapter< hardware_interface::PositionJointInterface, State > Class Template Reference

Adapter for a position-controlled hardware interface. Forwards desired positions as commands. More...

#include <hardware_interface_adapter.h>

Public Member Functions

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

Private Attributes

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

Detailed Description

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

Adapter for a position-controlled hardware interface. Forwards desired positions as commands.

The following is an example configuration of a controller that uses this adapter.

head_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- head_1_joint
- head_2_joint
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 95 of file hardware_interface_adapter.h.

Constructor & Destructor Documentation

Definition at line 98 of file hardware_interface_adapter.h.

Member Function Documentation

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

Definition at line 100 of file hardware_interface_adapter.h.

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

Definition at line 108 of file hardware_interface_adapter.h.

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

Definition at line 119 of file hardware_interface_adapter.h.

template<class State >
void HardwareInterfaceAdapter< hardware_interface::PositionJointInterface, State >::updateCommand ( const ros::Time ,
const ros::Duration ,
const State &  desired_state,
const State &   
)
inline

Definition at line 121 of file hardware_interface_adapter.h.

Member Data Documentation

template<class State >
std::vector<hardware_interface::JointHandle>* HardwareInterfaceAdapter< hardware_interface::PositionJointInterface, State >::joint_handles_ptr_
private

Definition at line 132 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 Thu Apr 11 2019 03:08:37