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
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_
00038 #define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_
00039
00040 #include <moveit/ompl_interface/parameterization/model_based_state_space.h>
00041
00042 namespace ompl_interface
00043 {
00044
00045 class PoseModelStateSpace : public ModelBasedStateSpace
00046 {
00047 public:
00048
00049 static const std::string PARAMETERIZATION_TYPE;
00050
00052 class StateType : public ModelBasedStateSpace::StateType
00053 {
00054 public:
00055 enum
00056 {
00057 JOINTS_COMPUTED = 256,
00058 POSE_COMPUTED = 512
00059 };
00060
00061 StateType() : ModelBasedStateSpace::StateType()
00062 {
00063 flags |= JOINTS_COMPUTED;
00064 }
00065
00066 bool jointsComputed() const
00067 {
00068 return flags & JOINTS_COMPUTED;
00069 }
00070
00071 bool poseComputed() const
00072 {
00073 return flags & POSE_COMPUTED;
00074 }
00075
00076 void setJointsComputed(bool value)
00077 {
00078 if (value)
00079 flags |= JOINTS_COMPUTED;
00080 else
00081 flags &= ~JOINTS_COMPUTED;
00082 }
00083
00084 void setPoseComputed(bool value)
00085 {
00086 if (value)
00087 flags |= POSE_COMPUTED;
00088 else
00089 flags &= ~POSE_COMPUTED;
00090 }
00091
00092 };
00093
00094 PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec);
00095 virtual ~PoseModelStateSpace();
00096
00097 virtual ompl::base::State* allocState() const;
00098 virtual void freeState(ompl::base::State *state) const;
00099 virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const;
00100 virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const;
00101 virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const;
00102 virtual double getMaximumExtent() const;
00103
00104 bool computeStateFK(ompl::base::State *state) const;
00105 bool computeStateIK(ompl::base::State *state) const;
00106 bool computeStateK(ompl::base::State *state) const;
00107
00108 virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
00109 virtual void copyToOMPLState(ompl::base::State *state, const robot_state::JointStateGroup* jsg) const;
00110 virtual void sanityChecks() const;
00111
00112 private:
00113
00114 struct PoseComponent
00115 {
00116 PoseComponent(const robot_model::JointModelGroup *subgroup);
00117
00118 bool computeStateFK(const ompl::base::StateSpace *full_state_space, ompl::base::State *full_state, ompl::base::State *state) const;
00119 bool computeStateIK(const ompl::base::StateSpace *full_state_space, ompl::base::State *full_state, ompl::base::State *state) const;
00120
00121 bool operator<(const PoseComponent &o) const
00122 {
00123 return subgroup_->getName() < o.subgroup_->getName();
00124 }
00125
00126 const robot_model::JointModelGroup *subgroup_;
00127 boost::shared_ptr<kinematics::KinematicsBase> kinematics_solver_;
00128 ompl::base::StateSpacePtr state_space_;
00129 std::vector<std::string> fk_link_;
00130 std::vector<std::string> joint_names_;
00131 std::vector<unsigned int> joint_val_count_;
00132 unsigned int variable_count_;
00133 };
00134
00135 void constructSpaceFromPoses();
00136 virtual void afterStateSample(ompl::base::State *sample) const;
00137
00138 std::vector<PoseComponent> poses_;
00139 double jump_factor_;
00140 };
00141
00142 }
00143
00144 #endif