#include <cassert>
#include <string>
#include <vector>
#include <memory>
#include <ros/node_handle.h>
#include <ros/time.h>
#include <control_toolbox/pid.h>
#include <hardware_interface/joint_command_interface.h>
#include <hardware_interface/posvel_command_interface.h>
#include <hardware_interface/posvelacc_command_interface.h>
Go to the source code of this file.
Classes | |
class | ClosedLoopHardwareInterfaceAdapter< State > |
Helper base class template for closed loop HardwareInterfaceAdapter implementations. More... | |
class | HardwareInterfaceAdapter< HardwareInterface, State > |
Helper class to simplify integrating the JointTrajectoryController with different hardware interfaces. More... | |
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. More... | |
class | HardwareInterfaceAdapter< hardware_interface::PositionJointInterface, State > |
Adapter for a position-controlled hardware interface. Forwards desired positions as commands. More... | |
class | HardwareInterfaceAdapter< hardware_interface::PosVelAccJointInterface, State > |
Adapter for a spline-controlled hardware interface. Forwards desired positions as commands. More... | |
class | HardwareInterfaceAdapter< hardware_interface::PosVelJointInterface, State > |
Adapter for a pos-vel hardware interface. Forwards desired positions with velcities as commands. More... | |
class | HardwareInterfaceAdapter< hardware_interface::VelocityJointInterface, State > |
Adapter for an velocity-controlled hardware interface. Maps position and velocity errors to velocity commands through a velocity PID loop. More... | |