37 #ifndef ACTIONLIB__SERVER__STATUS_TRACKER_H_ 38 #define ACTIONLIB__SERVER__STATUS_TRACKER_H_ 40 #include <actionlib_msgs/GoalID.h> 41 #include <actionlib_msgs/GoalStatus.h> 54 template<
class ActionSpec>
62 StatusTracker(
const actionlib_msgs::GoalID & goal_id,
unsigned int status);
78 #endif // ACTIONLIB__SERVER__STATUS_TRACKER_H_
ACTION_DEFINITION(ActionSpec)
boost::weak_ptr< void > handle_tracker_
actionlib_msgs::GoalStatus status_
A class for storing the status of each goal the action server is currently working on...
ros::Time handle_destruction_time_
boost::shared_ptr< const ActionGoal > goal_
StatusTracker(const actionlib_msgs::GoalID &goal_id, unsigned int status)
GoalIDGenerator id_generator_