1 #ifndef KINEMATICS_OBJECT_MOVE_HANDLER_HPP 2 #define KINEMATICS_OBJECT_MOVE_HANDLER_HPP 5 #include "HLR/ObjectMove.h" 6 #include "HLR/Progress.h" 8 #include <condition_variable> 70 HLR::ObjectMove::Response& res);
82 HLR::ObjectMove::Response& res);
94 HLR::ObjectMove::Response& res);
106 HLR::ObjectMove::Response& res);
125 void object_move_worker();
131 ros::Publisher progress_pub;
134 ros::ServiceServer service_move_start;
137 ros::ServiceServer service_move_stop;
140 ros::ServiceServer service_move_continue;
143 ros::ServiceServer service_move_cancel;
146 std::thread worker_thread;
149 HLR::Progress progress;
152 std::condition_variable cv;
155 std::queue<size_t> queue;
164 std::mutex worker_state_m;
bool object_move_continue(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the moevement needs to be continue Continue can be used when the movem...
bool object_move_start(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Start moving (grabbing) the specified cup based on ID If already moving ID is added to queue and exec...
ObjectMoveHandler()
Constructor.
virtual ~ObjectMoveHandler()
Destructor.
Interface to send commands to the Kinematics component Executes actions on the robotarm based in the ...
Definition: ObjectMoveHandler.hpp:26
bool object_move_stop(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the movement needs to stop Stop can be used when a movement is perform...
bool object_move_cancel(HLR::ObjectMove::Request &req, HLR::ObjectMove::Response &res)
Callback that is executed when the movement needs to be canceled Cup will be placed back on original ...
ObjectMoveHandler & operator=(const ObjectMoveHandler &omh)=delete
Copy assignment operator, deleted.