Provides a class for breadcrumbing an online trajectory. More...
#include <JointTrajectoryFollower.h>

Public Member Functions | |
| virtual double | getDuration () const |
| virtual const std::vector < std::string > & | getJointNames () const |
| virtual void | getNextPoint (sensor_msgs::JointState &nextPoint, ros::Duration &timeFromStart) |
| get next point | |
| OnlineJointTrajectoryFollower () | |
| void | setTrajectory (boost::shared_ptr< RosMsgJointTrajectory > trajectory_in, double timestep_in, double velocityFactor_in=1.) |
| set trajectory | |
| virtual | ~OnlineJointTrajectoryFollower () |
Private Attributes | |
| double | time |
| double | timestep |
| boost::shared_ptr < RosMsgJointTrajectory > | trajectory |
Provides a class for breadcrumbing an online trajectory.
Definition at line 100 of file JointTrajectoryFollower.h.
Definition at line 202 of file JointTrajectoryFollower.cpp.
| virtual OnlineJointTrajectoryFollower::~OnlineJointTrajectoryFollower | ( | ) | [inline, virtual] |
Definition at line 104 of file JointTrajectoryFollower.h.
| virtual double OnlineJointTrajectoryFollower::getDuration | ( | ) | const [inline, virtual] |
Implements JointTrajectoryFollower.
Definition at line 108 of file JointTrajectoryFollower.h.
| virtual const std::vector<std::string>& OnlineJointTrajectoryFollower::getJointNames | ( | ) | const [inline, virtual] |
Implements JointTrajectoryFollower.
Definition at line 106 of file JointTrajectoryFollower.h.
| void OnlineJointTrajectoryFollower::getNextPoint | ( | sensor_msgs::JointState & | nextPoint, |
| ros::Duration & | timeFromStart | ||
| ) | [virtual] |
get next point
Get the next point in the trajectory for the online joint.
| nextPoint | joint state of next point, returned |
| timeFromStart | time from start of next point, returned |
| nextPoint | Next joint state |
| timeFromStart | Time from the start of beginning of trajectory |
| runtime_error | If trajectory is inactive |
Implements JointTrajectoryFollower.
Definition at line 244 of file JointTrajectoryFollower.cpp.
| void OnlineJointTrajectoryFollower::setTrajectory | ( | boost::shared_ptr< RosMsgJointTrajectory > | trajectoryIn, |
| double | timestep_in, | ||
| double | velocityFactorIn = 1. |
||
| ) |
set trajectory
Set trajectory, velocity factor, and time step increments for an online joint.
| trajectory_in | new trajectory |
if there is an existing trajectory, it is preempted
| trajectoryIn | |
| timestep_in | |
| velocityFactorIn |
| runtime_error | If joint is currently following a trajectory |
Definition at line 215 of file JointTrajectoryFollower.cpp.
double OnlineJointTrajectoryFollower::time [private] |
Definition at line 128 of file JointTrajectoryFollower.h.
double OnlineJointTrajectoryFollower::timestep [private] |
Definition at line 128 of file JointTrajectoryFollower.h.
boost::shared_ptr<RosMsgJointTrajectory> OnlineJointTrajectoryFollower::trajectory [private] |
Definition at line 127 of file JointTrajectoryFollower.h.