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 MOVEIT_STATE_ADPATER_H_
00020 #define MOVEIT_STATE_ADPATER_H_
00021
00022 #include "descartes_core/robot_model.h"
00023 #include <descartes_trajectory/cart_trajectory_pt.h>
00024 #include <moveit/robot_model_loader/robot_model_loader.h>
00025 #include "moveit/robot_model/robot_model.h"
00026 #include "moveit/kinematics_base/kinematics_base.h"
00027 #include <moveit/planning_scene/planning_scene.h>
00028 #include <string>
00029
00030 namespace descartes_moveit
00031 {
00032
00036 class MoveitStateAdapter : public descartes_core::RobotModel
00037 {
00038
00039
00040 public:
00041 MoveitStateAdapter();
00042
00050 MoveitStateAdapter(const moveit::core::RobotState & robot_state, const std::string & group_name,
00051 const std::string & tool_frame, const std::string & world_frame);
00052
00053 virtual ~MoveitStateAdapter()
00054 {
00055 }
00056
00057 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00058 const std::string& world_frame,const std::string& tcp_frame);
00059
00060 virtual bool getIK(const Eigen::Affine3d &pose, const std::vector<double> &seed_state,
00061 std::vector<double> &joint_pose) const;
00062
00063 virtual bool getAllIK(const Eigen::Affine3d &pose, std::vector<std::vector<double> > &joint_poses) const;
00064
00065 virtual bool getFK(const std::vector<double> &joint_pose, Eigen::Affine3d &pose) const;
00066
00067 virtual bool isValid(const std::vector<double> &joint_pose) const;
00068
00069 virtual bool isValid(const Eigen::Affine3d &pose) const;
00070
00071 virtual int getDOF() const;
00072
00078 void setSeedStates(const std::vector<std::vector<double> >& seeds)
00079 {
00080 seed_states_ = seeds;
00081 }
00082
00086 const std::vector<std::vector<double> >& getSeedStates() const
00087 {
00088 return seed_states_;
00089 }
00090
00094 moveit::core::RobotStatePtr getState()
00095 {
00096 return robot_state_;
00097 }
00098
00099 virtual bool isValidMove(const std::vector<double>& from_joint_pose,
00100 const std::vector<double>& to_joint_pose,
00101 double dt) const;
00102
00103 protected:
00104
00111 bool getIK(const Eigen::Affine3d &pose, std::vector<double> &joint_pose) const;
00112
00123 bool isInCollision(const std::vector<double> &joint_pose) const;
00124
00125 std::vector<double> velocity_limits_;
00126 mutable moveit::core::RobotStatePtr robot_state_;
00127 planning_scene::PlanningScenePtr planning_scene_;
00128 robot_model_loader::RobotModelLoaderPtr robot_model_loader_;
00129 robot_model::RobotModelConstPtr robot_model_ptr_;
00130
00134 std::vector<std::vector<double> > seed_states_;
00135
00139 std::string group_name_;
00140
00144 std::string tool_frame_;
00145
00149 std::string world_frame_;
00150
00154 descartes_core::Frame world_to_root_;
00155
00156 };
00157
00158 }
00159
00160 #endif