#include <RosActionServer.h>
- Todo:
- write docs
Definition at line 32 of file RosActionServer.h.
◆ RosActionServer()
| ROSEE::RosActionServer::RosActionServer |
( |
std::string |
topicForAction, |
|
|
ros::NodeHandle * |
nh |
|
) |
| |
◆ ~RosActionServer()
| ROSEE::RosActionServer::~RosActionServer |
( |
| ) |
|
|
inline |
◆ abortGoal()
| void ROSEE::RosActionServer::abortGoal |
( |
std::string |
errorMsg = "" | ) |
|
◆ getGoal()
| rosee_msg::ROSEEActionControl ROSEE::RosActionServer::getGoal |
( |
| ) |
|
◆ getWantedNormError()
| double ROSEE::RosActionServer::getWantedNormError |
( |
| ) |
const |
in message there is a field where norm error of joint position can be set If it is not present in the message sent (thus it is 0) the DEFAULT_ERROR_NORM is used
Definition at line 42 of file RosActionServer.cpp.
◆ goalReceivedCallback()
| void ROSEE::RosActionServer::goalReceivedCallback |
( |
| ) |
|
|
protected |
◆ hasGoal()
| bool ROSEE::RosActionServer::hasGoal |
( |
| ) |
const |
◆ hasNewGoal()
| bool ROSEE::RosActionServer::hasNewGoal |
( |
| ) |
const |
◆ preemptReceivedCallback()
| void ROSEE::RosActionServer::preemptReceivedCallback |
( |
| ) |
|
|
protected |
◆ sendComplete()
| void ROSEE::RosActionServer::sendComplete |
( |
| ) |
|
◆ sendFeedback()
| void ROSEE::RosActionServer::sendFeedback |
( |
double |
completation_percentage, |
|
|
std::string |
currentAction |
|
) |
| |
send Feedback to the client who has requested the goal.
- Parameters
-
| completation_percentage | the percentae that tells how much we have completed the action requested |
| currentAction | current action that is running. If it is empty, it is taken the name of the action from member actionControlMsg . You should passed not empty string when dealing with timed action (passing the inner action of the timed one) |
Definition at line 95 of file RosActionServer.cpp.
◆ _actionServer
◆ actionControlMsg
| rosee_msg::ROSEEActionControl ROSEE::RosActionServer::actionControlMsg |
|
protected |
◆ goalInExecution
| bool ROSEE::RosActionServer::goalInExecution |
|
protected |
◆ newGoal
| bool ROSEE::RosActionServer::newGoal |
|
protected |
◆ nh
◆ topicForAction
| std::string ROSEE::RosActionServer::topicForAction |
|
protected |
◆ wantedNormError
| double ROSEE::RosActionServer::wantedNormError |
|
protected |
The documentation for this class was generated from the following files: