HLR  0.0.1
ObjectMoveHandler.hpp
1 #ifndef KINEMATICS_OBJECT_MOVE_HANDLER_HPP
2 #define KINEMATICS_OBJECT_MOVE_HANDLER_HPP
3 
4 #include <ros/ros.h>
5 #include "HLR/ObjectMove.h"
6 #include "HLR/Progress.h"
7 
8 #include <condition_variable>
9 #include <mutex>
10 #include <queue>
11 #include <thread>
12 
13 namespace HLR
14 {
15 namespace Kinematics
16 {
27 {
28 public:
31 
33  virtual ~ObjectMoveHandler();
34 
39  ObjectMoveHandler(const ObjectMoveHandler& omh) = delete;
40 
45  ObjectMoveHandler(ObjectMoveHandler&& omh) = delete;
46 
52  ObjectMoveHandler& operator=(const ObjectMoveHandler& omh) = delete;
53 
60 
69  bool object_move_start(HLR::ObjectMove::Request& req,
70  HLR::ObjectMove::Response& res);
71 
81  bool object_move_cancel(HLR::ObjectMove::Request& req,
82  HLR::ObjectMove::Response& res);
83 
93  bool object_move_continue(HLR::ObjectMove::Request& req,
94  HLR::ObjectMove::Response& res);
95 
105  bool object_move_stop(HLR::ObjectMove::Request& req,
106  HLR::ObjectMove::Response& res);
107 
108 private:
110  enum class State
111  {
113  idle = 0,
115  cont = 1,
117  stop = 2,
119  cancel = 3,
121  exit = 4
122  };
123 
125  void object_move_worker();
126 
128  ros::NodeHandle nh;
129 
131  ros::Publisher progress_pub;
132 
134  ros::ServiceServer service_move_start;
135 
137  ros::ServiceServer service_move_stop;
138 
140  ros::ServiceServer service_move_continue;
141 
143  ros::ServiceServer service_move_cancel;
144 
146  std::thread worker_thread;
147 
149  HLR::Progress progress;
150 
152  std::condition_variable cv;
153 
155  std::queue<size_t> queue;
156 
158  std::mutex queue_m;
159 
161  State worker_state;
162 
164  std::mutex worker_state_m;
165 };
166 
167 } // namespace Kinematics
168 } // namespace HLR
169 
170 #endif /* KINEMATICS_OBJECT_MOVE_HANDLER_HPP */
bool object_move_continue(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the moevement needs to be continue Continue can be used when the movem...
bool object_move_start(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Start moving (grabbing) the specified cup based on ID If already moving ID is added to queue and exec...
virtual ~ObjectMoveHandler()
Destructor.
Interface to send commands to the Kinematics component Executes actions on the robotarm based in the ...
Definition: ObjectMoveHandler.hpp:26
bool object_move_stop(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the movement needs to stop Stop can be used when a movement is perform...
bool object_move_cancel(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the movement needs to be canceled Cup will be placed back on original ...
ObjectMoveHandler & operator=(const ObjectMoveHandler &omh)=delete
Copy assignment operator, deleted.