HLR  0.0.1
Driver.hpp
1 #ifndef KINEMATICS_RV2AJ_DRIVER_HPP
2 #define KINEMATICS_RV2AJ_DRIVER_HPP
3 
4 #include <ros/ros.h>
5 #include "HLR/RV2AJDriverClear.h"
6 #include "HLR/RV2AJDriverContinue.h"
7 #include "HLR/RV2AJDriverPause.h"
8 #include "HLR/RV2AJDriverQueueAdd.h"
9 #include "HLR/RV2AJDriverQueueCount.h"
10 #include "std_msgs/String.h"
11 
12 #include <array>
13 #include <condition_variable>
14 #include <mutex>
15 #include <optional>
16 #include <queue>
17 #include <thread>
18 
19 #include "Serial.hpp"
20 
21 namespace HLR
22 {
23 namespace Kinematics
24 {
25 namespace RV2AJ
26 {
28 class Driver
29 {
30 public:
37  Driver(bool simulation, const std::optional<std::string>& serial_path);
38 
40  virtual ~Driver();
41 
46  Driver(const Driver& d) = delete;
47 
52  Driver(Driver&& d) = delete;
53 
59  Driver& operator=(const Driver& d) = delete;
60 
66  Driver& operator=(Driver&& d) = delete;
67 
74  bool cont(HLR::RV2AJDriverContinue::Request& req,
75  HLR::RV2AJDriverContinue::Response& res);
76 
83  bool pause(HLR::RV2AJDriverPause::Request& req,
84  HLR::RV2AJDriverPause::Response& res);
85 
92  bool clear(HLR::RV2AJDriverClear::Request& req,
93  HLR::RV2AJDriverClear::Response& res);
94 
101  bool queue_count(HLR::RV2AJDriverQueueCount::Request& req,
102  HLR::RV2AJDriverQueueCount::Response& res);
103 
110  bool queue_add(HLR::RV2AJDriverQueueAdd::Request& req,
111  HLR::RV2AJDriverQueueAdd::Response& res);
112 
113 private:
120  struct Command
121  {
126  std::array<std::string, 3> to_mb4() const;
127 
129  double base;
131  double shoulder;
133  double elbow;
135  double j4;
137  double wrist;
139  double wrist_rotate;
141  double j7;
143  double speed;
144  };
145 
146  enum class State
147  {
149  cont = 0,
151  pause = 1,
153  exit = 2
154  };
155 
165  bool tx(const Command& cmd);
166 
172  void tx(const std::string& mb4);
173 
178  void rx();
179 
184  void rx_sub_callback(const std_msgs::String::ConstPtr& msg);
185 
187  void work();
188 
190  void work_reply();
191 
193  std::size_t device_count = 0;
194 
196  ros::NodeHandle nh;
197 
199  ros::Publisher tx_pub;
200 
202  bool tx_abort = false;
203 
205  std::mutex tx_abort_m;
206 
208  bool rx_block = true;
209 
211  std::mutex rx_block_m;
212 
214  std::condition_variable rx_block_cv;
215 
217  ros::Subscriber rx_sub;
218 
220  ros::ServiceServer srv_continue;
221 
223  ros::ServiceServer srv_pause;
224 
226  ros::ServiceServer srv_clear;
227 
229  ros::ServiceServer srv_queue_count;
230 
232  ros::ServiceServer srv_queue_add;
233 
235  std::thread worker;
236 
238  State worker_state = State::cont;
239 
241  std::mutex worker_state_m;
242 
244  std::queue<Command> commands;
245 
247  std::mutex commands_m;
248 
250  std::condition_variable commands_cv;
251 
253  std::thread worker_reply;
254 
256  State worker_reply_state = State::cont;
257 
259  std::mutex worker_reply_state_m;
260 
262  std::queue<std::string> replies;
263 
265  std::mutex replies_m;
266 
268  std::condition_variable replies_cv;
269 
271  Serial serial;
272 };
273 } // namespace RV2AJ
274 } // namespace Kinematics
275 } // namespace HLR
276 
277 #endif /* KINEMATICS_RV2AJ_DRIVER_HPP */
Driver for the Mitsubishi RV2-AJ.
Definition: Driver.hpp:28
bool queue_add(HLR::RV2AJDriverQueueAdd::Request &req, HLR::RV2AJDriverQueueAdd::Response &res)
Add requested command to the queue if compliant.
virtual ~Driver()
Destructor.
OO wrapper around POSIX serial devices.
Definition: Serial.hpp:13
bool pause(HLR::RV2AJDriverPause::Request &req, HLR::RV2AJDriverPause::Response &res)
Pause processing events in queue.
bool clear(HLR::RV2AJDriverClear::Request &req, HLR::RV2AJDriverClear::Response &res)
Clears all to-be processed events in queue.
bool cont(HLR::RV2AJDriverContinue::Request &req, HLR::RV2AJDriverContinue::Response &res)
Continue processing events in queue.
bool queue_count(HLR::RV2AJDriverQueueCount::Request &req, HLR::RV2AJDriverQueueCount::Response &res)
Returns the number of elements currently inside the queue.
Driver(bool simulation, const std::optional< std::string > &serial_path)
Constructor.
Driver & operator=(const Driver &d)=delete
Copy assignment operator, deleted.