ROS-UVS  1.0.0
A Minimalistic ROS Library for Visual Constraint Minimization through Uncalibrated Visual Servoing
 All Classes Files Functions Variables
robot_controller.h
Go to the documentation of this file.
1 #ifndef ROBOT_CONTROLLER_H
2 #define ROBOT_CONTROLLER_H
3 
4 #include <Eigen/Core>
5 
7  public:
8  virtual bool delta_move(const Eigen::VectorXd& move) = 0;
9  virtual bool rt_delta_move(const Eigen::VectorXd& delta) = 0;
10  virtual Eigen::VectorXd get_jnt_state() = 0;
11  virtual Eigen::VectorXd get_used_jnt_state() = 0;
12 
13  virtual size_t get_dof() {
14  ROS_INFO_STREAM("WRONG!");
15  return 0;
16  };
17 
18  virtual std::vector<int> get_used_joints() = 0;
19 
20  virtual void set_target_joint_pose(Eigen::VectorXd target) = 0;
21  virtual Eigen::VectorXd map_joints(const Eigen::VectorXd& delta) = 0;
22  virtual void set_used_joints(std::string) = 0;
23  virtual void set_used_joints(std::vector<int> new_joints) = 0;
24 };
25 
26 #endif //ROBOT_CONTROLLER_H
virtual std::vector< int > get_used_joints()=0
virtual bool rt_delta_move(const Eigen::VectorXd &delta)=0
virtual void set_used_joints(std::string)=0
Definition: robot_controller.h:6
virtual Eigen::VectorXd get_used_jnt_state()=0
virtual size_t get_dof()
Definition: robot_controller.h:13
virtual bool delta_move(const Eigen::VectorXd &move)=0
virtual Eigen::VectorXd get_jnt_state()=0
virtual void set_target_joint_pose(Eigen::VectorXd target)=0
virtual Eigen::VectorXd map_joints(const Eigen::VectorXd &delta)=0