HLR  0.0.1
RobotController.hpp
1 #ifndef KINEMATICS_ROBOTCONTROLLER_HPP
2 #define KINEMATICS_ROBOTCONTROLLER_HPP
3 
4 #include <ros/ros.h>
5 #include "Planners/Planner.hpp"
6 #include <CGAL/Simple_cartesian.h>
7 #include <CGAL/Surface_mesh.h>
8 #include <Kinematics/ConcurrentQueue.hpp>
9 #include <Kinematics/Matrix.hpp>
10 
11 #include <mutex>
12 #include <stdexcept>
13 #include <thread>
14 #include <unordered_set>
15 
16 #include "RobotDriverHandler.hpp"
17 
18 namespace HLR
19 {
20 namespace Kinematics
21 {
26 {
30  std::uint32_t id;
31 
36 
41 
45  bool is_cup;
46 
50  bool has_speed;
51 
55  CGAL::Surface_mesh<CGAL::Simple_cartesian<double>::Point_3> polyhedron;
56 };
57 
62 {
66  idle,
67 
72 
77 
81  giving_cup,
82 
86  cancelling,
87 
91  stopped
92 };
93 
98 enum class ArmError
99 {
104 
110 
116 };
117 
124 {
125 public:
130  enum class Event
131  {
135  move_to_ready,
136 
140  pick_up_cup,
141 
145  stop,
146 
150  resume,
151 
155  cancel,
156 
160  terminate
161  };
162 
169 
173  virtual ~RobotController();
174 
179  RobotController(const RobotController& rc) = delete;
180 
185  RobotController(RobotController&& rc) = delete;
186 
192  RobotController& operator=(const RobotController& rc) = delete;
193 
199  RobotController& operator=(RobotController&& rc) = delete;
200 
206  RobotControllerState get_state() const;
207 
218  void pick_up_cup(std::uint32_t id);
219 
225  void move_stop();
226 
232  void move_continue();
233 
241  void move_cancel();
242 
249  void remove_object(const EnvironmentObject& obj);
250 
256  void add_object(EnvironmentObject&& obj);
257 
267  void set_error_callback(const std::function<void(ArmError)>& cb);
268 
274  void set_state_change_callback(
275  const std::function<void(RobotControllerState)>& cb);
276 
277 private:
283  void set_state(RobotControllerState state);
284 
289  void position_reached();
290 
295  void event_handler();
296 
300  void move_to_ready_handler();
301 
305  void pick_up_cup_handler();
306 
310  void stop_handler();
311 
315  void resume_handler();
316 
320  void cancel_handler();
321 
325  const Matrix<double, 3, 1> target_position = {{0.0}, {0.4}, {0.2}};
326 
330  const Matrix<double, 3, 1> ready_pos = {{0.357}, {0.216506}, {0}};
331 
335  const double speed = 100;
336 
341  const double distance_from_cup = 0.06;
342 
346  const double lift_distance = 0.10;
347 
351  const double angle_step_size = 5;
352 
356  const double euclidean_step_size = 0.05;
357 
361  std::function<void(ArmError)> error_callback;
362 
366  std::function<void(RobotControllerState)> state_callback;
367 
373 
378 
382  mutable std::mutex state_m;
383 
387  Matrix<double, 3, 1> cup_position;
388 
392  std::unordered_map<std::uint32_t, EnvironmentObject> objects;
393 
397  mutable std::recursive_mutex objects_m;
398 
403  std::thread worker;
404 
408  ConcurrentQueue<Event> events;
409 
413  RobotDriverHandler& driver;
414 };
415 
416 } // namespace Kinematics
417 } // namespace HLR
418 
419 #endif
Matrix< double, 3, 1 > velocity
The velocity vector of the object.
Definition: RobotController.hpp:40
Robot arm is moving to ready position,.
CGAL::Surface_mesh< CGAL::Simple_cartesian< double >::Point_3 > polyhedron
The CGAL polyhedron data. This can be used for collision checking.
Definition: RobotController.hpp:55
RobotControllerState
The current state of the robot controller.
Definition: RobotController.hpp:61
The arm has stopped due to a safety concern.
std::uint32_t id
The id of the object.
Definition: RobotController.hpp:30
Describes an object that is detected in the environment.
Definition: RobotController.hpp:25
This class contains the main logic of the robotic arm. It handles the calculation of robotic path and...
Definition: RobotController.hpp:123
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:50
The arm has stopped because no valid path was found to execute the given action.
Concrete handle on the robot using the ROS interface.
Definition: RobotDriverHandler.hpp:19
Event
Internal event class. These events are send to the worker thread and handled accordingly.
Definition: RobotController.hpp:130
Robot arm is moving gripper to surround the cup.
bool is_cup
Whether this object is a cup.
Definition: RobotController.hpp:45
The robot arm is currently idle.
ArmError
Enum containing possible reasons for the robot arm not being able to succesfully execute the specifie...
Definition: RobotController.hpp:98
Matrix< double, 3, 1 > position
The position vector of the object.
Definition: RobotController.hpp:35