A class for storing the status of each goal the action server is currently working on. More...
#include <status_tracker.h>
Public Member Functions | |
StatusTracker (const actionlib_msgs::GoalID &goal_id, unsigned int status) | |
StatusTracker (const boost::shared_ptr< const ActionGoal > &goal) | |
Public Attributes | |
boost::shared_ptr< const ActionGoal > | goal_ |
ros::Time | handle_destruction_time_ |
boost::weak_ptr< void > | handle_tracker_ |
actionlib_msgs::GoalStatus | status_ |
Private Attributes | |
GoalIDGenerator | id_generator_ |
A class for storing the status of each goal the action server is currently working on.
Definition at line 90 of file status_tracker.h.
actionlib::StatusTracker< ActionSpec >::StatusTracker | ( | const actionlib_msgs::GoalID & | goal_id, |
unsigned int | status | ||
) |
Definition at line 77 of file status_tracker_imp.h.
actionlib::StatusTracker< ActionSpec >::StatusTracker | ( | const boost::shared_ptr< const ActionGoal > & | goal | ) |
Definition at line 86 of file status_tracker_imp.h.
boost::shared_ptr<const ActionGoal> actionlib::StatusTracker< ActionSpec >::goal_ |
Definition at line 101 of file status_tracker.h.
ros::Time actionlib::StatusTracker< ActionSpec >::handle_destruction_time_ |
Definition at line 104 of file status_tracker.h.
boost::weak_ptr<void> actionlib::StatusTracker< ActionSpec >::handle_tracker_ |
Definition at line 102 of file status_tracker.h.
|
private |
Definition at line 107 of file status_tracker.h.
actionlib_msgs::GoalStatus actionlib::StatusTracker< ActionSpec >::status_ |
Definition at line 103 of file status_tracker.h.