ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ROSEE::RosActionServer Class Reference

#include <RosActionServer.h>

+ Collaboration diagram for ROSEE::RosActionServer:

Public Member Functions

 RosActionServer (std::string topicForAction, ros::NodeHandle *nh)
 
 ~RosActionServer ()
 
rosee_msg::ROSEEActionControl getGoal ()
 
bool hasGoal () const
 
bool hasNewGoal () const
 
double 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 More...
 
void sendFeedback (double completation_percentage, std::string currentAction)
 send Feedback to the client who has requested the goal. More...
 
void sendComplete ()
 
void abortGoal (std::string errorMsg="")
 

Protected Member Functions

void goalReceivedCallback ()
 
void preemptReceivedCallback ()
 

Protected Attributes

ros::NodeHandle * nh
 
std::string topicForAction
 
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
 
rosee_msg::ROSEEActionControl actionControlMsg
 
bool goalInExecution
 
bool newGoal
 
double wantedNormError
 

Detailed Description

Todo:
write docs

Definition at line 32 of file RosActionServer.h.

Constructor & Destructor Documentation

ROSEE::RosActionServer::RosActionServer ( std::string  topicForAction,
ros::NodeHandle *  nh 
)

Definition at line 19 of file RosActionServer.cpp.

19  :
20  _actionServer(*nh, topicForAction, false) {
21 
22  this->nh = nh;
24  goalInExecution = false;
25  newGoal = false;
26 
27  _actionServer.registerGoalCallback (boost::bind(&RosActionServer::goalReceivedCallback, this));
28  _actionServer.registerPreemptCallback (boost::bind (&RosActionServer::preemptReceivedCallback, this));
29 
30  _actionServer.start();
31 
32 }
ros::NodeHandle * nh
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
ROSEE::RosActionServer::~RosActionServer ( )
inline

Definition at line 36 of file RosActionServer.h.

36 {};

Member Function Documentation

void ROSEE::RosActionServer::abortGoal ( std::string  errorMsg = "")

Definition at line 83 of file RosActionServer.cpp.

83  {
84  ROS_INFO_STREAM("ROSACTION SERVER Aborted goal");
85  rosee_msg::ROSEECommandResult result;
86  result.completed_action = actionControlMsg;
87  _actionServer.setAborted(result, errorMsg);
88  newGoal = false;
89  goalInExecution = false;
91 
92 
93 }
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.

46  {
47  if (goalInExecution) {
48  newGoal = false;
49  return actionControlMsg;
50  } else {
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();
54  }
55 }
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.

42  {
43  return wantedNormError;
44 }
void ROSEE::RosActionServer::goalReceivedCallback ( )
protected

Definition at line 58 of file RosActionServer.cpp.

58  {
59 
60  //ROS_INFO_STREAM (goal_action.
61  goalInExecution = true;
62  newGoal = true;
63  this->actionControlMsg = _actionServer.acceptNewGoal()->goal_action;
64 
66 
67  ROS_INFO_STREAM ("ROSACTION SERVER received goal: '" << this->actionControlMsg.action_name << "'");
68 
69 
70 }
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
bool ROSEE::RosActionServer::hasGoal ( ) const

Definition at line 34 of file RosActionServer.cpp.

34  {
35  return goalInExecution;
36 }
bool ROSEE::RosActionServer::hasNewGoal ( ) const

Definition at line 38 of file RosActionServer.cpp.

38  {
39  return newGoal;
40 }
void ROSEE::RosActionServer::preemptReceivedCallback ( )
protected

Definition at line 72 of file RosActionServer.cpp.

72  {
73 
74  ROS_INFO_STREAM("ROSACTION SERVER Preempted old goal");
75  goalInExecution = false;
76  newGoal = false;
78  // set the action state to preempted
79  _actionServer.setPreempted();
80 
81 }
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer
#define DEFAULT_ERROR_NORM
void ROSEE::RosActionServer::sendComplete ( )

Definition at line 111 of file RosActionServer.cpp.

111  {
112 
113  ROS_INFO_STREAM("ROSACTION SERVER Sending final result completed ");
114  goalInExecution = false;
115  newGoal = false; //even if here should be already false
117 
118  rosee_msg::ROSEECommandResult result;
119  result.completed_action = actionControlMsg;
120 
121  _actionServer.setSucceeded ( result );
122  //TODO reinitialize actionControlMsg here or not?
123 
124 }
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_percentagethe percentae that tells how much we have completed the action requested
currentActioncurrent 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.

95  {
96 
97  ROS_INFO_STREAM("ROSACTION SERVER Sending feedback " << completation_percentage );
98 
99  rosee_msg::ROSEECommandFeedback feedback;
100  feedback.completation_percentage = completation_percentage;
101  if (currentAction.size() == 0) {
102  feedback.action_name_current = actionControlMsg.action_name;
103  } else {
104  feedback.action_name_current = currentAction;
105  }
106 
107  _actionServer.publishFeedback(feedback);
108 
109 }
rosee_msg::ROSEEActionControl actionControlMsg
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer

Member Data Documentation

actionlib::SimpleActionServer<rosee_msg::ROSEECommandAction> ROSEE::RosActionServer::_actionServer
protected

Definition at line 65 of file RosActionServer.h.

rosee_msg::ROSEEActionControl ROSEE::RosActionServer::actionControlMsg
protected

Definition at line 66 of file RosActionServer.h.

bool ROSEE::RosActionServer::goalInExecution
protected

Definition at line 67 of file RosActionServer.h.

bool ROSEE::RosActionServer::newGoal
protected

Definition at line 68 of file RosActionServer.h.

ros::NodeHandle* ROSEE::RosActionServer::nh
protected

Definition at line 63 of file RosActionServer.h.

std::string ROSEE::RosActionServer::topicForAction
protected

Definition at line 64 of file RosActionServer.h.

double ROSEE::RosActionServer::wantedNormError
protected

Definition at line 69 of file RosActionServer.h.


The documentation for this class was generated from the following files: