Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #ifndef ROBOT_KINEMATICS_H_
00020 #define ROBOT_KINEMATICS_H_
00021
00022
00023 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00024 #include "descartes_core/utils.h"
00025
00026 namespace descartes_core
00027 {
00028
00029 DESCARTES_CLASS_FORWARD(RobotModel);
00030
00040 class RobotModel
00041 {
00042 public:
00043
00044 virtual ~RobotModel(){}
00045
00053 virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00054 std::vector<double> &joint_pose) const = 0;
00055
00064 virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const = 0;
00065
00072 virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const = 0;
00073
00078 virtual int getDOF() const = 0;
00079
00085 virtual bool isValid(const std::vector<double> &joint_pose) const = 0;
00086
00092 virtual bool isValid(const Eigen::Affine3d &pose) const = 0;
00093
00102 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00103 const std::string& world_frame, const std::string& tcp_frame) = 0;
00104
00109 virtual void setCheckCollisions(bool check_collisions)
00110 {
00111 check_collisions_ = check_collisions;
00112 }
00113
00118 virtual bool getCheckCollisions()
00119 {
00120 return check_collisions_;
00121 }
00122
00131 virtual bool isValidMove(const std::vector<double>& from_joint_pose, const std::vector<double>& to_joint_pose,
00132 double dt) const = 0;
00133
00134 protected:
00135
00136 RobotModel(): check_collisions_(false){}
00137
00138 bool check_collisions_;
00139
00140 };
00141
00142 }
00143
00144
00145
00146
00147 #endif