#include <RosActionServer.h>
- Todo:
- write docs
Definition at line 32 of file RosActionServer.h.
ROSEE::RosActionServer::RosActionServer |
( |
std::string |
topicForAction, |
|
|
ros::NodeHandle * |
nh |
|
) |
| |
Definition at line 19 of file RosActionServer.cpp.
std::string topicForAction
void preemptReceivedCallback()
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
void goalReceivedCallback()
ROSEE::RosActionServer::~RosActionServer |
( |
| ) |
|
|
inline |
void ROSEE::RosActionServer::abortGoal |
( |
std::string |
errorMsg = "" | ) |
|
Definition at line 83 of file RosActionServer.cpp.
84 ROS_INFO_STREAM(
"ROSACTION SERVER Aborted goal");
85 rosee_msg::ROSEECommandResult result;
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
rosee_msg::ROSEEActionControl ROSEE::RosActionServer::getGoal |
( |
| ) |
|
Definition at line 46 of file RosActionServer.cpp.
51 ROS_WARN_STREAM (
"ROSACTION SERVER no goal is in execution (no one has" <<
52 "arrived or the last one is already completed. EMPTY GOAL RETURNING");
53 return rosee_msg::ROSEEActionControl();
rosee_msg::ROSEEActionControl actionControlMsg
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.
void ROSEE::RosActionServer::goalReceivedCallback |
( |
| ) |
|
|
protected |
Definition at line 58 of file RosActionServer.cpp.
67 ROS_INFO_STREAM (
"ROSACTION SERVER received goal: '" << this->
actionControlMsg.action_name <<
"'");
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
bool ROSEE::RosActionServer::hasGoal |
( |
| ) |
const |
bool ROSEE::RosActionServer::hasNewGoal |
( |
| ) |
const |
void ROSEE::RosActionServer::preemptReceivedCallback |
( |
| ) |
|
|
protected |
Definition at line 72 of file RosActionServer.cpp.
74 ROS_INFO_STREAM(
"ROSACTION SERVER Preempted old goal");
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
void ROSEE::RosActionServer::sendComplete |
( |
| ) |
|
Definition at line 111 of file RosActionServer.cpp.
113 ROS_INFO_STREAM(
"ROSACTION SERVER Sending final result completed ");
118 rosee_msg::ROSEECommandResult result;
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
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.
97 ROS_INFO_STREAM(
"ROSACTION SERVER Sending feedback " << completation_percentage );
99 rosee_msg::ROSEECommandFeedback feedback;
100 feedback.completation_percentage = completation_percentage;
101 if (currentAction.size() == 0) {
104 feedback.action_name_current = currentAction;
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
actionlib::SimpleActionServer<rosee_msg::ROSEECommandAction> ROSEE::RosActionServer::_actionServer |
|
protected |
rosee_msg::ROSEEActionControl ROSEE::RosActionServer::actionControlMsg |
|
protected |
bool ROSEE::RosActionServer::goalInExecution |
|
protected |
bool ROSEE::RosActionServer::newGoal |
|
protected |
ros::NodeHandle* ROSEE::RosActionServer::nh |
|
protected |
std::string ROSEE::RosActionServer::topicForAction |
|
protected |
double ROSEE::RosActionServer::wantedNormError |
|
protected |
The documentation for this class was generated from the following files: