Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
JointTrajectoryManager Class Reference

Provides a helper for managing joint trajectories. More...

#include <JointTrajectoryManager.h>

Inheritance diagram for JointTrajectoryManager:
Inheritance graph
[legend]

List of all members.

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

Detailed Description

Provides a helper for managing joint trajectories.

Definition at line 19 of file JointTrajectoryManager.h.


Member Typedef Documentation

typedef std::map<std::string, actionlib_msgs::GoalID> JointTrajectoryManager::JointGoalMap_type [protected]

Definition at line 45 of file JointTrajectoryManager.h.


Constructor & Destructor Documentation

Constructor for the Joint Trajectory Manager (empty)

Definition at line 8 of file JointTrajectoryManager.cpp.

Definition at line 13 of file JointTrajectoryManager.cpp.


Member Function Documentation

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.

Parameters:
trajectorynew trajectory
Returns:
void
Exceptions:
runtime_errora joint in trajectory is already part of an active goal

if there is an existing trajectory, it is preempted

Parameters:
jointNamesVector of joint names to add to the Goal Map
goalIdGoal 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

Parameters:
goalIdgoal ID to check
Returns:
bool active state

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.

Returns:
The string stream representation of the Joint Goal Map

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.

Parameters:
jointNamesPointer to vector of joint names to remove from the Joint Goal Map
Exceptions:
runtime_errorIf 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.

Parameters:
goalPointer to GoalID to remove from the Joint Goal Map
Exceptions:
runtime_errorIf one of the GoalIDs specified is an active goal

Definition at line 75 of file JointTrajectoryManager.cpp.


Member Data Documentation

Definition at line 46 of file JointTrajectoryManager.h.


The documentation for this class was generated from the following files:


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:54