Line data Source code
1 : /*
2 : * Copyright 2020 <copyright holder> <email>
3 : *
4 : * Licensed under the Apache License, Version 2.0 (the "License");
5 : * you may not use this file except in compliance with the License.
6 : * You may obtain a copy of the License at
7 : *
8 : * http://www.apache.org/licenses/LICENSE-2.0
9 : *
10 : * Unless required by applicable law or agreed to in writing, software
11 : * distributed under the License is distributed on an "AS IS" BASIS,
12 : * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 : * See the License for the specific language governing permissions and
14 : * limitations under the License.
15 : */
16 :
17 : #ifndef ROSACTIONSERVER_H
18 : #define ROSACTIONSERVER_H
19 :
20 : #include <string>
21 : #include <ros/ros.h>
22 : #include <ros/console.h>
23 : #include <actionlib/server/simple_action_server.h>
24 : #include <rosee_msg/ROSEECommandAction.h>
25 :
26 : #define DEFAULT_ERROR_NORM 0.01
27 :
28 : namespace ROSEE {
29 : /**
30 : * @todo write docs
31 : */
32 : class RosActionServer {
33 :
34 : public:
35 : RosActionServer(std::string topicForAction, ros::NodeHandle *nh);
36 41 : ~RosActionServer() {};
37 :
38 : rosee_msg::ROSEEActionControl getGoal();
39 : bool hasGoal() const;
40 : bool hasNewGoal() const;
41 :
42 : /**
43 : * @brief in message there is a field where norm error of joint position can be set
44 : * If it is not present in the message sent (thus it is 0) the DEFAULT_ERROR_NORM is used
45 : */
46 : double getWantedNormError() const;
47 :
48 : /**
49 : * @brief send Feedback to the client who has requested the goal.
50 : *
51 : * @param completation_percentage the percentae that tells how much we have completed
52 : * the action requested
53 : * @param currentAction current action that is running. If it is empty, it is taken the name
54 : * of the action from member \ref actionControlMsg . You should passed not empty string when
55 : * dealing with timed action (passing the inner action of the timed one)
56 : */
57 : void sendFeedback(double completation_percentage, std::string currentAction) ;
58 : void sendComplete () ;
59 : void abortGoal(std::string errorMsg = "");
60 :
61 :
62 : protected:
63 : ros::NodeHandle* nh;
64 : std::string topicForAction;
65 : actionlib::SimpleActionServer <rosee_msg::ROSEECommandAction> _actionServer;
66 : rosee_msg::ROSEEActionControl actionControlMsg;
67 : bool goalInExecution;
68 : bool newGoal;
69 : double wantedNormError;
70 :
71 : void goalReceivedCallback ();
72 : void preemptReceivedCallback ();
73 :
74 :
75 : };
76 :
77 : }
78 :
79 : #endif // ROSACTIONSERVER_H
|