ROSEndEffector
ROS End-Effector package: provides a ROS-based set of standard interfaces to command robotics end-effectors in an agnostic fashion.
RosActionServer.h
Go to the documentation of this file.
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 {
33 
34 public:
35  RosActionServer(std::string topicForAction, ros::NodeHandle *nh);
37 
38  rosee_msg::ROSEEActionControl getGoal();
39  bool hasGoal() const;
40  bool hasNewGoal() const;
41 
46  double getWantedNormError() const;
47 
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;
68  bool newGoal;
70 
71  void goalReceivedCallback ();
73 
74 
75 };
76 
77 }
78 
79 #endif // ROSACTIONSERVER_H
void sendFeedback(double completation_percentage, std::string currentAction)
send Feedback to the client who has requested the goal.
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...
ros::NodeHandle * nh
RosActionServer(std::string topicForAction, ros::NodeHandle *nh)
rosee_msg::ROSEEActionControl actionControlMsg
void abortGoal(std::string errorMsg="")
rosee_msg::ROSEEActionControl getGoal()
actionlib::SimpleActionServer< rosee_msg::ROSEECommandAction > _actionServer