Provides a an abstract class for breadcrumbing a trajectory and maintaining status. More...
#include <JointTrajectoryFollower.h>
Public Member Functions | |
virtual void | abort (const std::string &msg=std::string()) |
abort stops trajectory and sets status to aborted | |
virtual double | getDuration () const =0 |
virtual const std::vector < std::string > & | getJointNames () const =0 |
virtual void | getNextPoint (sensor_msgs::JointState &nextPoint, ros::Duration &timeFromStart)=0 |
get next point | |
virtual bool | isActive () const |
isActive | |
JointTrajectoryFollower () | |
Constructor for Joint Trajectory Follower. | |
virtual void | preempt (const std::string &msg=std::string()) |
preempt stops trajectory and sets status to preempted | |
virtual | ~JointTrajectoryFollower () |
Public Attributes | |
GoalManager | goalManager |
double | velocityFactor |
Provides a an abstract class for breadcrumbing a trajectory and maintaining status.
Definition at line 21 of file JointTrajectoryFollower.h.
Constructor for Joint Trajectory Follower.
Definition at line 9 of file JointTrajectoryFollower.cpp.
virtual JointTrajectoryFollower::~JointTrajectoryFollower | ( | ) | [inline, virtual] |
Definition at line 25 of file JointTrajectoryFollower.h.
void JointTrajectoryFollower::abort | ( | const std::string & | msg = std::string() | ) | [virtual] |
abort stops trajectory and sets status to aborted
Set Ready State to false and abort Joint Trajectory Follower.
Definition at line 19 of file JointTrajectoryFollower.cpp.
virtual double JointTrajectoryFollower::getDuration | ( | ) | const [pure virtual] |
Implemented in OnlineJointTrajectoryFollower, and PreplannedJointTrajectoryFollower.
virtual const std::vector<std::string>& JointTrajectoryFollower::getJointNames | ( | ) | const [pure virtual] |
Implemented in OnlineJointTrajectoryFollower, and PreplannedJointTrajectoryFollower.
virtual void JointTrajectoryFollower::getNextPoint | ( | sensor_msgs::JointState & | nextPoint, |
ros::Duration & | timeFromStart | ||
) | [pure virtual] |
get next point
nextPoint | joint state of next point, returned |
timeFromStart | time from start of next point, returned |
Implemented in OnlineJointTrajectoryFollower, and PreplannedJointTrajectoryFollower.
virtual bool JointTrajectoryFollower::isActive | ( | ) | const [inline, virtual] |
isActive
false if done with trajectory or reset, true otherwise
Definition at line 36 of file JointTrajectoryFollower.h.
void JointTrajectoryFollower::preempt | ( | const std::string & | msg = std::string() | ) | [virtual] |
preempt stops trajectory and sets status to preempted
Set Ready State to false and preempt Joint Trajectory Follower.
Definition at line 30 of file JointTrajectoryFollower.cpp.
Definition at line 55 of file JointTrajectoryFollower.h.
Definition at line 56 of file JointTrajectoryFollower.h.