RosReflexxesInterface.h
Go to the documentation of this file.
1 //
2 // Created by oke on 15.11.18.
3 //
4 
5 #ifndef ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H
6 #define ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H
7 
8 #include <vector>
9 
10 #include <ros/ros.h>
11 
13 
14 public:
15 
16  virtual ~RosReflexxesInterface() {};
20  virtual bool init(ros::NodeHandle nh) = 0;
21  virtual void starting(const std::vector<double> &initial_command) = 0;
22  virtual std::vector<double> update() = 0; //advance reflexxes and return current state
23 
24  std::vector<double> update(const std::vector<double> &command) {
25  set_target_command(command);
26  return update();
27  }
28 
32  virtual std::vector<double> get_target_command() = 0;
33  virtual void set_target_command(const std::vector<double> &command) = 0;
34  virtual void set_target_position(const std::vector<double> &t_pos) = 0;
35  virtual void set_target_velocity(const std::vector<double> &t_vel) = 0;
36 
40  virtual std::vector<double> get_current_position() = 0;
41  virtual std::vector<double> get_current_velocity() = 0;
42  virtual std::vector<double> get_current_acceleration() = 0;
43 };
44 
45 
46 #endif //ROS_REFLEXXES_ROSREFLEXXESINTERFACE_H
virtual void set_target_position(const std::vector< double > &t_pos)=0
virtual std::vector< double > get_current_velocity()=0
virtual std::vector< double > get_target_command()=0
virtual void set_target_command(const std::vector< double > &command)=0
std::vector< double > update(const std::vector< double > &command)
virtual void starting(const std::vector< double > &initial_command)=0
ROSLIB_DECL std::string command(const std::string &cmd)
virtual std::vector< double > get_current_acceleration()=0
virtual void set_target_velocity(const std::vector< double > &t_vel)=0
virtual std::vector< double > update()=0
virtual bool init(ros::NodeHandle nh)=0
virtual std::vector< double > get_current_position()=0


ros_reflexxes
Author(s):
autogenerated on Sat Nov 21 2020 03:17:43