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 
84  stopped
85 };
86 
91 enum class ArmError
92 {
97 
103 
109 };
110 
117 {
118 public:
123  enum class Event
124  {
128  move_to_ready,
129 
133  pick_up_cup,
134 
139  move_stop,
140 
144  move_continue,
145 
149  move_cancel,
150 
154  arm_move_complete,
155 
159  terminate
160  };
161 
168 
172  virtual ~RobotController();
173 
178  RobotController(const RobotController& rc) = delete;
179 
184  RobotController(RobotController&& rc) = delete;
185 
191  RobotController& operator=(const RobotController& rc) = delete;
192 
198  RobotController& operator=(RobotController&& rc) = delete;
199 
205  RobotControllerState get_state() const;
206 
217  void pick_up_cup(std::uint32_t id);
218 
224  void move_stop();
225 
231  void move_continue();
232 
240  void move_cancel();
241 
248  void remove_object(const EnvironmentObject& obj);
249 
255  void add_object(EnvironmentObject&& obj);
256 
266  void set_error_callback(const std::function<void(ArmError)>& cb);
267 
268 private:
276  void move_to_position(const Matrix<double, 3, 1>& pos, const Planner& planner, double speed);
277 
282  void event_handler();
283 
287  void move_to_ready_handler();
288 
292  void pick_up_cup_handler();
293 
297  void arm_move_complete_handler();
298 
302  void move_stop_handler();
303 
307  void move_continue_handler();
308 
312  void move_cancel_handler();
313 
317  const Matrix<double, 3, 1> target_position = {{0}, {0}, {0}};
318 
322  const Matrix<double, 3, 1> ready_pos = {{0.357}, {0.216506}, {0}};
323 
328  const double ground_level = 0;
329 
333  const double angle_step_size = 1;
334 
338  const double euclidean_step_size = 0.01;
339 
344  std::function<void(ArmError)> error_callback;
345 
350  bool is_carrying = false;
351 
356 
360  mutable std::mutex state_m;
361 
365  Matrix<double, 3, 1> cup_position;
366 
370  std::unordered_map<std::uint32_t, EnvironmentObject> objects;
371 
375  mutable std::mutex objects_m;
376 
381  std::thread worker;
382 
386  ConcurrentQueue<Event> events;
387 
391  RobotDriverHandler& driver;
392 };
393 
394 } // namespace Kinematics
395 } // namespace HLR
396 
397 #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 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:116
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:123
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:91
Matrix< double, 3, 1 > position
The position vector of the object.
Definition: RobotController.hpp:33