List of all members
HardwareInterfaceAdapter< hardware_interface::VelocityJointInterface, State > Class Template Reference

Adapter for an velocity-controlled hardware interface. Maps position and velocity errors to velocity commands through a velocity PID loop. More...

#include <hardware_interface_adapter.h>

Inheritance diagram for HardwareInterfaceAdapter< hardware_interface::VelocityJointInterface, State >:
Inheritance graph
[legend]

Additional Inherited Members

- Public Member Functions inherited from ClosedLoopHardwareInterfaceAdapter< State >
 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)
 

Detailed Description

template<class State>
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.

The following is an example configuration of a controller that uses this adapter. Notice the gains and velocity_ff entries:

head_controller:
type: "velocity_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}
velocity_ff:
head_1_joint: 1.0
head_2_joint: 1.0
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 253 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