HLR  0.0.1
RobotDriverHandler.hpp
1 #ifndef KINEMATICS_ROSROBOTDRIVERHANDLER_HPP
2 #define KINEMATICS_ROSROBOTDRIVERHANDLER_HPP
3 
4 #include <atomic>
5 #include <unordered_map>
6 
7 #include <ros/ros.h>
8 #include "std_msgs/UInt64.h"
9 #include "RobotDriverHandler.hpp"
10 #include <Kinematics/Matrix.hpp>
11 
12 namespace HLR
13 {
14 namespace Kinematics
15 {
20 {
21 public:
24 
26  virtual ~RobotDriverHandler() = default;
27 
32  RobotDriverHandler(const RobotDriverHandler& rdh) = delete;
33 
38  RobotDriverHandler(RobotDriverHandler&& rdh) = delete;
39 
45  RobotDriverHandler& operator=(const RobotDriverHandler& rdh) = delete;
46 
53 
59  Matrix<double, 5, 1> get_arm_state() const noexcept;
60 
66  std::vector<Matrix<double, 5, 1>> get_path() const noexcept;
67 
75  std::uint64_t get_offset_current_move() const;
76 
86  void move(const std::vector<Matrix<double, 5, 1>>& path, double speed);
87 
93  void stop();
94 
100  void set_move_complete_handler(const std::function<void()>& handler);
101 
102 private:
108  void sub_move_complete(const std_msgs::UInt64::ConstPtr& id);
109 
113  std::function<void()> move_complete_handler;
114 
118  ros::NodeHandle nh;
119 
123  ros::Subscriber id_subscriber;
124 
128  ros::ServiceClient driver_stop;
129 
133  ros::ServiceClient driver_add;
134 
138  std::atomic<Matrix<double, 5, 1>> current_arm_state;
139 
143  std::vector<std::uint64_t> path_ids;
144 
148  std::uint64_t last_id_complete = std::numeric_limits<std::uint64_t>::max();
149 
154  std::vector<Matrix<double, 5, 1>> path;
155 };
156 
157 } // namespace Kinematics
158 } // namespace HLR
159 
160 #endif
std::uint64_t get_offset_current_move() const
Get the offset of the last move that was completed by the robotarm.
void stop()
Stop the robot arm.
RobotDriverHandler & operator=(const RobotDriverHandler &rdh)=delete
Copy assignment operator, deleted.
void set_move_complete_handler(const std::function< void()> &handler)
Set the move complete handler.
virtual ~RobotDriverHandler()=default
Destructor.
Concrete handle on the robot using the ROS interface.
Definition: RobotDriverHandler.hpp:19
Matrix< double, 5, 1 > get_arm_state() const noexcept
Get the current arm position.
std::vector< Matrix< double, 5, 1 > > get_path() const noexcept
Get the path the robot arm is moving to.
void move(const std::vector< Matrix< double, 5, 1 >> &path, double speed)
Move the robot arm along a path.
Create a matrix with numerical values.
Definition: Matrix.hpp:22