manages goal status. More...
#include <GoalManager.h>
Public Member Functions | |
| const actionlib_msgs::GoalStatus & | getStatus () const |
| maintain a goalStatus. | |
| GoalManager () | |
| GoalManager (const GoalManager &in) | |
| bool | isReady () const |
| allow maintainance of a state outside of just the goal status message. | |
| void | reset (bool readyState=true) |
| void | setGoalId (const actionlib_msgs::GoalID &goalId) |
| void | setGoalId (const ros::Time &stamp, const std::string &id) |
| void | setReadyState (bool ready_in) |
| void | setStatus (const actionlib_msgs::GoalStatus::_status_type &status) |
| void | setText (const std::string &text) |
| virtual | ~GoalManager () |
Private Attributes | |
| actionlib_msgs::GoalStatus | goalStatus |
| bool | ready |
manages goal status.
Definition at line 17 of file GoalManager.h.
| GoalManager::GoalManager | ( | ) | [inline] |
Definition at line 20 of file GoalManager.h.
| GoalManager::GoalManager | ( | const GoalManager & | in | ) | [inline] |
Definition at line 21 of file GoalManager.h.
| virtual GoalManager::~GoalManager | ( | ) | [inline, virtual] |
Definition at line 22 of file GoalManager.h.
| const actionlib_msgs::GoalStatus& GoalManager::getStatus | ( | ) | const [inline] |
maintain a goalStatus.
Definition at line 27 of file GoalManager.h.
| bool GoalManager::isReady | ( | ) | const [inline] |
allow maintainance of a state outside of just the goal status message.
Definition at line 37 of file GoalManager.h.
| void GoalManager::reset | ( | bool | readyState = true | ) | [inline] |
Definition at line 39 of file GoalManager.h.
| void GoalManager::setGoalId | ( | const actionlib_msgs::GoalID & | goalId | ) | [inline] |
Definition at line 28 of file GoalManager.h.
| void GoalManager::setGoalId | ( | const ros::Time & | stamp, |
| const std::string & | id | ||
| ) | [inline] |
Definition at line 29 of file GoalManager.h.
| void GoalManager::setReadyState | ( | bool | ready_in | ) | [inline] |
Definition at line 38 of file GoalManager.h.
| void GoalManager::setStatus | ( | const actionlib_msgs::GoalStatus::_status_type & | status | ) | [inline] |
Definition at line 31 of file GoalManager.h.
| void GoalManager::setText | ( | const std::string & | text | ) | [inline] |
Definition at line 32 of file GoalManager.h.
actionlib_msgs::GoalStatus GoalManager::goalStatus [private] |
Definition at line 47 of file GoalManager.h.
bool GoalManager::ready [private] |
Definition at line 49 of file GoalManager.h.