HLR  0.0.1
ObjectMoveHandler.hpp
1 #ifndef KINEMATICS_OBJECT_MOVE_HANDLER_HPP
2 #define KINEMATICS_OBJECT_MOVE_HANDLER_HPP
3 
4 #include <ros/ros.h>
5 #include "HLR/ObjectMoveAction.h"
6 #include "HLR/ObjectMoveStart.h"
7 #include "HLR/Progress.h"
8 
9 #include "RobotController.hpp"
10 
11 namespace HLR
12 {
13 namespace Kinematics
14 {
25 {
26 public:
33 
37  virtual ~ObjectMoveHandler() = default;
38 
43  ObjectMoveHandler(const ObjectMoveHandler& omh) = delete;
44 
49  ObjectMoveHandler(ObjectMoveHandler&& omh) = delete;
50 
56  ObjectMoveHandler& operator=(const ObjectMoveHandler& omh) = delete;
57 
64 
73  bool object_move_start(HLR::ObjectMoveStart::Request& req,
74  HLR::ObjectMoveStart::Response& res);
75 
85  bool object_move_cancel(HLR::ObjectMoveAction::Request& req,
86  HLR::ObjectMoveAction::Response& res);
87 
97  bool object_move_continue(HLR::ObjectMoveAction::Request& req,
98  HLR::ObjectMoveAction::Response& res);
99 
109  bool object_move_stop(HLR::ObjectMoveAction::Request& req,
110  HLR::ObjectMoveAction::Response& res);
111 
112 private:
119  std::uint8_t convert_controller_state_to_ros_msg(
120  RobotControllerState state) const noexcept;
121 
125  ros::NodeHandle nh;
126 
130  ros::Publisher state_pub;
131 
135  ros::ServiceServer service_move_start;
136 
140  ros::ServiceServer service_move_stop;
141 
145  ros::ServiceServer service_move_continue;
146 
150  ros::ServiceServer service_move_cancel;
151 
155  HLR::Progress progress;
156 
161  RobotController& controller;
162 };
163 
164 } // namespace Kinematics
165 } // namespace HLR
166 
167 #endif /* KINEMATICS_OBJECT_MOVE_HANDLER_HPP */
virtual ~ObjectMoveHandler()=default
Destructor.
bool object_move_start(HLR::ObjectMoveStart::Request &req, HLR::ObjectMoveStart::Response &res)
Start moving (grabbing) the specified cup based on ID If already moving ID is added to queue and exec...
bool object_move_stop(HLR::ObjectMoveAction::Request &req, HLR::ObjectMoveAction::Response &res)
Callback that is executed when the movement needs to stop Stop can be used when a movement is perform...
bool object_move_continue(HLR::ObjectMoveAction::Request &req, HLR::ObjectMoveAction::Response &res)
Callback that is executed when the moevement needs to be continue Continue can be used when the movem...
ObjectMoveHandler(RobotController &controller)
Constructor.
RobotControllerState
The current state of the robot controller.
Definition: RobotController.hpp:61
This class contains the main logic of the robotic arm. It handles the calculation of robotic path and...
Definition: RobotController.hpp:138
Interface to send commands to the Kinematics component Executes actions on the robotarm based in the ...
Definition: ObjectMoveHandler.hpp:24
ObjectMoveHandler & operator=(const ObjectMoveHandler &omh)=delete
Copy assignment operator, deleted.
bool object_move_cancel(HLR::ObjectMoveAction::Request &req, HLR::ObjectMoveAction::Response &res)
Callback that is executed when the movement needs to be canceled Cup will be placed back on original ...