Provides a helper for managing joint trajectories. More...
#include <JointTrajectoryManager.h>

Public Member Functions | |
| void | addToJointGoalMap (const std::vector< std::string > &jointNames, const actionlib_msgs::GoalID goalId) |
| set trajectory | |
| JointTrajectoryManager () | |
| Constructor for the Joint Trajectory Manager (empty) | |
| void | removeFromJointGoalMap (const std::vector< std::string > &jointNames) |
| Remove the pairs with the specified jointNames from the Joint Goal Map. | |
| void | removeFromJointGoalMap (const actionlib_msgs::GoalID &goal) |
| Remove the pair with the specified GoalID from the Joint Goal Map. | |
| virtual | ~JointTrajectoryManager () |
Protected Types | |
| typedef std::map< std::string, actionlib_msgs::GoalID > | JointGoalMap_type |
Protected Member Functions | |
| virtual bool | isActive (const actionlib_msgs::GoalID &goalId) const =0 |
| is goal active | |
| std::string | jointGoalMapToString (void) const |
| Convert the Joint Goal Map into a String. | |
Protected Attributes | |
| JointGoalMap_type | jointGoalMap |
Provides a helper for managing joint trajectories.
Definition at line 19 of file JointTrajectoryManager.h.
typedef std::map<std::string, actionlib_msgs::GoalID> JointTrajectoryManager::JointGoalMap_type [protected] |
Definition at line 45 of file JointTrajectoryManager.h.
Constructor for the Joint Trajectory Manager (empty)
Definition at line 8 of file JointTrajectoryManager.cpp.
| JointTrajectoryManager::~JointTrajectoryManager | ( | ) | [virtual] |
Definition at line 13 of file JointTrajectoryManager.cpp.
| void JointTrajectoryManager::addToJointGoalMap | ( | const std::vector< std::string > & | jointNames, |
| const actionlib_msgs::GoalID | goalId | ||
| ) |
set trajectory
Add specified joints and goal ID pairs to the Joint Goal Map.
| trajectory | new trajectory |
| runtime_error | a joint in trajectory is already part of an active goal |
if there is an existing trajectory, it is preempted
| jointNames | Vector of joint names to add to the Goal Map |
| goalId | Goal Ids to pair with the joint names and insert into the Joint Goal Map |
Definition at line 24 of file JointTrajectoryManager.cpp.
| virtual bool JointTrajectoryManager::isActive | ( | const actionlib_msgs::GoalID & | goalId | ) | const [protected, pure virtual] |
is goal active
| goalId | goal ID to check |
derived class must provide a way to check this
Implemented in TrajectoryManager, and JointTrajectoryManagerTest::derivedManager.
| std::string JointTrajectoryManager::jointGoalMapToString | ( | void | ) | const [protected] |
Convert the Joint Goal Map into a String.
Definition at line 108 of file JointTrajectoryManager.cpp.
| void JointTrajectoryManager::removeFromJointGoalMap | ( | const std::vector< std::string > & | jointNames | ) |
Remove the pairs with the specified jointNames from the Joint Goal Map.
| jointNames | Pointer to vector of joint names to remove from the Joint Goal Map |
| runtime_error | If one of the joint names specified is an active goal |
Definition at line 43 of file JointTrajectoryManager.cpp.
| void JointTrajectoryManager::removeFromJointGoalMap | ( | const actionlib_msgs::GoalID & | goal | ) |
Remove the pair with the specified GoalID from the Joint Goal Map.
| goal | Pointer to GoalID to remove from the Joint Goal Map |
| runtime_error | If one of the GoalIDs specified is an active goal |
Definition at line 75 of file JointTrajectoryManager.cpp.
Definition at line 46 of file JointTrajectoryManager.h.