The GoalStatusSender class handles goal status messages. A pure virtual writeStatus function is used to actually send the message. More...
#include <GoalStatusSender.h>
Public Member Functions | |
| unsigned int | addStatus (const actionlib_msgs::GoalStatus &status) |
| addStatus | |
| unsigned int | addStatus (const ros::Time &stamp, const std::string &id, const actionlib_msgs::GoalStatus::_status_type &status, const std::string &text) |
| addStatus | |
| void | clearStatusMessage () |
| Clear the status message. | |
| GoalStatusSender (const std::string &name) | |
| Constructor for Goal Status Sender. | |
| void | removeStatus (unsigned int index) |
| removeStatus | |
| void | sendStatusMessage (bool clear=false) |
| Send a status message. | |
| void | sendStatusMessage (const actionlib_msgs::GoalStatus &status, bool clear=false) |
| Send a status message. | |
| void | sendStatusMessage (const ros::Time &stamp, const std::string &id, const actionlib_msgs::GoalStatus::_status_type &status, const std::string &text, bool clear=false) |
| Send a status message. | |
| void | sendStatusMessage (const actionlib_msgs::GoalStatus::_status_type &status, const std::string &text, bool clear=false) |
| Send a status message. | |
| actionlib_msgs::GoalStatus & | status (unsigned int index) |
| Retrieve status at the given index. | |
| const actionlib_msgs::GoalStatus & | status (unsigned int index) const |
| Retrieve status at the given index. | |
| virtual | ~GoalStatusSender () |
Protected Member Functions | |
| virtual void | writeStatus (const actionlib_msgs::GoalStatusArray &goalStatusMsg_out)=0 |
Private Attributes | |
| actionlib_msgs::GoalStatusArray | goalStatusMsg |
The GoalStatusSender class handles goal status messages. A pure virtual writeStatus function is used to actually send the message.
Definition at line 15 of file GoalStatusSender.h.
| GoalStatusSender::GoalStatusSender | ( | const std::string & | name | ) |
Constructor for Goal Status Sender.
Definition at line 7 of file GoalStatusSender.cpp.
| GoalStatusSender::~GoalStatusSender | ( | ) | [virtual] |
Definition at line 12 of file GoalStatusSender.cpp.
| unsigned int GoalStatusSender::addStatus | ( | const actionlib_msgs::GoalStatus & | status | ) |
addStatus
Add status to the statuS_list.
| status | New status to be added to the status_list |
Definition at line 87 of file GoalStatusSender.cpp.
| unsigned int GoalStatusSender::addStatus | ( | const ros::Time & | stamp, |
| const std::string & | id, | ||
| const actionlib_msgs::GoalStatus::_status_type & | status, | ||
| const std::string & | text | ||
| ) |
addStatus
Send a status message.
| clear | If "clear" is true, then clear the status message at the end |
Definition at line 98 of file GoalStatusSender.cpp.
| void GoalStatusSender::clearStatusMessage | ( | ) |
Clear the status message.
Definition at line 76 of file GoalStatusSender.cpp.
| void GoalStatusSender::removeStatus | ( | unsigned int | index | ) |
removeStatus
Remove status at the given index.
| index |
| out_of_range | index out of range |
| index | The index to erase in the status_list |
| std::out_of_range | If the index is larger than the size of the status_list |
Definition at line 158 of file GoalStatusSender.cpp.
| void GoalStatusSender::sendStatusMessage | ( | bool | clear = false | ) |
Send a status message.
| clear | If "clear" is true, then clear the status message at the end |
Definition at line 21 of file GoalStatusSender.cpp.
| void GoalStatusSender::sendStatusMessage | ( | const actionlib_msgs::GoalStatus & | status, |
| bool | clear = false |
||
| ) |
Send a status message.
| status | Status message to add |
| clear | Sent after the status is added |
Definition at line 41 of file GoalStatusSender.cpp.
| void GoalStatusSender::sendStatusMessage | ( | const ros::Time & | stamp, |
| const std::string & | id, | ||
| const actionlib_msgs::GoalStatus::_status_type & | status, | ||
| const std::string & | text, | ||
| bool | clear = false |
||
| ) |
Send a status message.
| clear | If "clear" is true, then clear the status message at the end |
Definition at line 52 of file GoalStatusSender.cpp.
| void GoalStatusSender::sendStatusMessage | ( | const actionlib_msgs::GoalStatus::_status_type & | status, |
| const std::string & | text, | ||
| bool | clear = false |
||
| ) |
Send a status message.
| clear | If "clear" is true, then clear the status message at the end |
Definition at line 65 of file GoalStatusSender.cpp.
| actionlib_msgs::GoalStatus & GoalStatusSender::status | ( | unsigned int | index | ) |
Retrieve status at the given index.
| index | The index to check in the status_list |
| std::out_of_range | If the index is larger than the size of the status_list |
Definition at line 117 of file GoalStatusSender.cpp.
| const actionlib_msgs::GoalStatus & GoalStatusSender::status | ( | unsigned int | index | ) | const |
Retrieve status at the given index.
| index | The index to check in the status_list |
| std::out_of_range | If the index is larger than the size of the status_list |
Definition at line 138 of file GoalStatusSender.cpp.
| virtual void GoalStatusSender::writeStatus | ( | const actionlib_msgs::GoalStatusArray & | goalStatusMsg_out | ) | [protected, pure virtual] |
actionlib_msgs::GoalStatusArray GoalStatusSender::goalStatusMsg [private] |
Definition at line 58 of file GoalStatusSender.h.