20 _actionServer(*nh, topicForAction, false) {
35 return goalInExecution;
43 return wantedNormError;
47 if (goalInExecution) {
49 return actionControlMsg;
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();
61 goalInExecution =
true;
63 this->actionControlMsg = _actionServer.acceptNewGoal()->goal_action;
65 wantedNormError = actionControlMsg.error_norm == 0 ?
DEFAULT_ERROR_NORM : actionControlMsg.error_norm;
67 ROS_INFO_STREAM (
"ROSACTION SERVER received goal: '" << this->actionControlMsg.action_name <<
"'");
75 goalInExecution =
false;
79 _actionServer.setPreempted();
85 rosee_msg::ROSEECommandResult result;
86 result.completed_action = actionControlMsg;
87 _actionServer.setAborted(result, errorMsg);
89 goalInExecution =
false;
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) {
102 feedback.action_name_current = actionControlMsg.action_name;
104 feedback.action_name_current = currentAction;
107 _actionServer.publishFeedback(feedback);
114 goalInExecution =
false;
118 rosee_msg::ROSEECommandResult result;
119 result.completed_action = actionControlMsg;
121 _actionServer.setSucceeded ( result );