1 #ifndef KINEMATICS_ROBOTCONTROLLER_HPP 2 #define KINEMATICS_ROBOTCONTROLLER_HPP 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> 14 #include <unordered_set> 16 #include "RobotDriverHandler.hpp" 55 CGAL::Surface_mesh<CGAL::Simple_cartesian<double>::Point_3>
polyhedron;
218 void pick_up_cup(std::uint32_t
id);
232 void move_continue();
267 void set_error_callback(
const std::function<
void(
ArmError)>& cb);
274 void set_state_change_callback(
289 void position_reached();
295 void event_handler();
300 void move_to_ready_handler();
305 void pick_up_cup_handler();
315 void resume_handler();
320 void cancel_handler();
335 const double speed = 100;
341 const double distance_from_cup = 0.06;
346 const double lift_distance = 0.10;
351 const double angle_step_size = 5;
356 const double euclidean_step_size = 0.05;
361 std::function<void(ArmError)> error_callback;
366 std::function<void(RobotControllerState)> state_callback;
382 mutable std::mutex state_m;
392 std::unordered_map<std::uint32_t, EnvironmentObject> objects;
397 mutable std::recursive_mutex objects_m;
Matrix< double, 3, 1 > velocity
The velocity vector of the object.
Definition: RobotController.hpp:40
Robot arm is moving to cup.
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'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.
Calculating the robot path to take.
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