HLR  0.0.1
RobotController.hpp
1 #ifndef KINEMATICS_ROBOTCONTROLLER_HPP
2 #define KINEMATICS_ROBOTCONTROLLER_HPP
3 
4 #include <ros/ros.h>
5 #include "Planner.hpp"
6 #include <Kinematics/ConcurrentQueue.hpp>
7 #include <Kinematics/Matrix.hpp>
8 
9 #include <mutex>
10 #include <stdexcept>
11 #include <thread>
12 #include <unordered_set>
13 
14 #include "RobotDriverHandler.hpp"
15 
16 namespace HLR
17 {
18 namespace Kinematics
19 {
24 {
28  std::uint32_t id;
29 
34 
39 
43  bool is_cup;
44 
48  bool has_speed;
49 
53  std::string polyhedron;
54 };
55 
60 {
64  init,
65 
69  idle,
70 
75 
80 
85 
90 
94  stopped
95 };
96 
101 enum class ArmError
102 {
107 
113 
119 };
120 
127 {
128 public:
133  enum class Event
134  {
138  move_to_ready,
139 
143  move_to_cup,
144 
148  pick_up_cup_stage1,
149 
153  pick_up_cup_stage2,
154 
159  move_stop,
160 
164  move_continue,
165 
169  move_cancel,
170 
174  terminate
175  };
176 
183 
187  virtual ~RobotController();
188 
193  RobotController(const RobotController& rc) = delete;
194 
199  RobotController(RobotController&& rc) = delete;
200 
206  RobotController& operator=(const RobotController& rc) = delete;
207 
213  RobotController& operator=(RobotController&& rc) = delete;
214 
220  RobotControllerState get_state() const;
221 
232  void pick_up_cup(std::uint32_t id);
233 
239  void move_stop();
240 
246  void move_continue();
247 
255  void move_cancel();
256 
263  void remove_object(const EnvironmentObject& obj);
264 
270  void add_object(EnvironmentObject&& obj);
271 
281  void set_error_callback(const std::function<void(ArmError)>& cb);
282 
283 private:
288  void position_reached();
289 
297  void move_to_position(const Matrix<double, 3, 1>& pos,
298  const Planner& planner,
299  double speed);
300 
305  void event_handler();
306 
310  void move_to_ready_handler();
311 
315  void pick_up_cup_handler();
316 
320  void pick_up_cup_stage1_handler();
321 
325  void pick_up_cup_stage2_handler();
326 
330  void move_stop_handler();
331 
335  void move_continue_handler();
336 
340  void move_cancel_handler();
341 
345  const Matrix<double, 3, 1> target_position = {{0}, {0}, {0}};
346 
350  const Matrix<double, 3, 1> ready_pos = {{0.357}, {0.216506}, {0}};
351 
356  const double ground_level = 0;
357 
362  const double distance_from_cup = 0.07;
363 
367  const double angle_step_size = 1;
368 
372  const double euclidean_step_size = 0.05;
373 
378  std::function<void(ArmError)> error_callback;
379 
384  bool is_carrying = false;
385 
390 
394  mutable std::mutex state_m;
395 
399  Matrix<double, 3, 1> cup_position;
400 
404  std::unordered_map<std::uint32_t, EnvironmentObject> objects;
405 
409  mutable std::mutex objects_m;
410 
415  std::thread worker;
416 
420  ConcurrentQueue<Event> events;
421 
425  RobotDriverHandler& driver;
426 };
427 
428 } // namespace Kinematics
429 } // namespace HLR
430 
431 #endif
Matrix< double, 3, 1 > velocity
The velocity vector of the object.
Definition: RobotController.hpp:38
Abstract class that forces.
Definition: Planner.hpp:15
Robot arm is moving gripper to surround the cup.
Robot arm is moving to ready position,.
RobotControllerState
The current state of the robot controller.
Definition: RobotController.hpp:59
The arm has stopped due to a safety concern.
std::uint32_t id
The id of the object.
Definition: RobotController.hpp:28
Describes an object that is detected in the environment.
Definition: RobotController.hpp:23
This class contains the main logic of the robotic arm. It handles the calculation of robotic path and...
Definition: RobotController.hpp:126
The arm couldn&#39;t be moved because there is an underlying driver error.
Robot arm is currently stopped.
bool has_speed
Whether this object has a valid speed.
Definition: RobotController.hpp:48
The arm has stopped because no valid path was found to execute the given action.
Interface that exposes the interface to the robotarm.
Definition: RobotDriverHandler.hpp:14
Event
Internal event class. These events are send to the worker thread and handled accordingly.
Definition: RobotController.hpp:133
bool is_cup
Whether this object is a cup.
Definition: RobotController.hpp:43
Is idle waiting to pick up a cup.
std::string polyhedron
The CGAL polyhedron data. This can be used for collision checking.
Definition: RobotController.hpp:53
ArmError
Enum containing possible reasons for the robot arm not being able to succesfully execute the specifie...
Definition: RobotController.hpp:101
Matrix< double, 3, 1 > position
The position vector of the object.
Definition: RobotController.hpp:33