Helper class to simplify integrating the JointTrajectoryController with different hardware interfaces. More...
#include <hardware_interface_adapter.h>
Public Member Functions | |
bool | init (std::vector< typename HardwareInterface::ResourceHandleType > &joint_handles, ros::NodeHandle &controller_nh) |
void | starting (const ros::Time &time) |
void | stopping (const ros::Time &time) |
void | updateCommand (const ros::Time &time, const ros::Duration &period, const State &desired_state, const State &state_error) |
Helper class to simplify integrating the JointTrajectoryController with different hardware interfaces.
Use one of the avaialble template specializations of this class (or create your own) to adapt the JointTrajectoryController to a specidfic hardware interface.
Definition at line 55 of file hardware_interface_adapter.h.
bool HardwareInterfaceAdapter< HardwareInterface, State >::init | ( | std::vector< typename HardwareInterface::ResourceHandleType > & | joint_handles, |
ros::NodeHandle & | controller_nh | ||
) | [inline] |
Definition at line 58 of file hardware_interface_adapter.h.
void HardwareInterfaceAdapter< HardwareInterface, State >::starting | ( | const ros::Time & | time | ) | [inline] |
Definition at line 63 of file hardware_interface_adapter.h.
void HardwareInterfaceAdapter< HardwareInterface, State >::stopping | ( | const ros::Time & | time | ) | [inline] |
Definition at line 64 of file hardware_interface_adapter.h.
void HardwareInterfaceAdapter< HardwareInterface, State >::updateCommand | ( | const ros::Time & | time, |
const ros::Duration & | period, | ||
const State & | desired_state, | ||
const State & | state_error | ||
) | [inline] |
Definition at line 66 of file hardware_interface_adapter.h.