HLR  0.0.1
RobotDriverHandler.hpp
1 #ifndef KINEMATICS_ROBOTDRIVERHANDLER_HPP
2 #define KINEMATICS_ROBOTDRIVERHANDLER_HPP
3 
4 #include <ros/ros.h>
5 #include <Kinematics/Matrix.hpp>
6 
7 namespace HLR
8 {
9 namespace Kinematics
10 {
15 {
16 public:
22  virtual Matrix<double, 5, 1> get_arm_state() const noexcept = 0;
23 
29  void set_move_complete_handler(const std::function<void()>& handler);
30 
37  virtual void move(const std::vector<Matrix<double, 5, 1>>& path,
38  double speed) = 0;
39 
43  virtual void stop() = 0;
44 
45 private:
49  std::function<void()> move_complete_handler;
50 };
51 
52 } // namespace Kinematics
53 } // namespace HLR
54 
55 #endif
virtual void stop()=0
Stop the robotarm if it is moving/.
virtual Matrix< double, 5, 1 > get_arm_state() const noexcept=0
Get the current position of the robot arm.
void set_move_complete_handler(const std::function< void()> &handler)
Set the move complete handler.
Interface that exposes the interface to the robotarm.
Definition: RobotDriverHandler.hpp:14
virtual void move(const std::vector< Matrix< double, 5, 1 >> &path, double speed)=0
Move the robot arm along a path.
Create a matrix with numerical values.
Definition: Matrix.hpp:22