1 #ifndef KINEMATICS_ROBOTCONTROLLER_HPP 2 #define KINEMATICS_ROBOTCONTROLLER_HPP 6 #include <Kinematics/ConcurrentQueue.hpp> 7 #include <Kinematics/Matrix.hpp> 12 #include <unordered_set> 14 #include "RobotDriverHandler.hpp" 217 void pick_up_cup(std::uint32_t
id);
231 void move_continue();
266 void set_error_callback(
const std::function<
void(
ArmError)>& cb);
282 void event_handler();
287 void move_to_ready_handler();
292 void pick_up_cup_handler();
297 void arm_move_complete_handler();
302 void move_stop_handler();
307 void move_continue_handler();
312 void move_cancel_handler();
328 const double ground_level = 0;
333 const double angle_step_size = 1;
338 const double euclidean_step_size = 0.01;
344 std::function<void(ArmError)> error_callback;
350 bool is_carrying =
false;
360 mutable std::mutex state_m;
370 std::unordered_map<std::uint32_t, EnvironmentObject> objects;
375 mutable std::mutex objects_m;
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.
Robot arm is moving to cup.
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'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