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_MODEL_BASED_STATE_SPACE_
00038 #define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_
00039
00040 #include <ompl/base/StateSpace.h>
00041 #include <moveit/robot_model/robot_model.h>
00042 #include <moveit/robot_state/robot_state.h>
00043 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00044 #include <moveit/constraint_samplers/constraint_sampler.h>
00045
00046 namespace ompl_interface
00047 {
00048
00049 typedef boost::function<bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction;
00050 typedef boost::function<double(const ompl::base::State *state1, const ompl::base::State *state2)> DistanceFunction;
00051
00052 struct ModelBasedStateSpaceSpecification
00053 {
00054 ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr &robot_model,
00055 const robot_model::JointModelGroup *jmg)
00056 : robot_model_(robot_model)
00057 , joint_model_group_(jmg)
00058 {
00059 }
00060
00061 ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr &robot_model,
00062 const std::string &group_name)
00063 : robot_model_(robot_model)
00064 , joint_model_group_(robot_model_->getJointModelGroup(group_name))
00065 {
00066 if (!joint_model_group_)
00067 throw std::runtime_error("Group '" + group_name + "' was not found");
00068 }
00069
00070 robot_model::RobotModelConstPtr robot_model_;
00071 const robot_model::JointModelGroup *joint_model_group_;
00072 robot_model::JointBoundsVector joint_bounds_;
00073 };
00074
00075 class ModelBasedStateSpace : public ompl::base::StateSpace
00076 {
00077 public:
00078
00079 class StateType : public ompl::base::State
00080 {
00081 public:
00082
00083 enum
00084 {
00085 VALIDITY_KNOWN = 1,
00086 GOAL_DISTANCE_KNOWN = 2,
00087 VALIDITY_TRUE = 4,
00088 IS_START_STATE = 8,
00089 IS_GOAL_STATE = 16
00090 };
00091
00092 StateType()
00093 : ompl::base::State()
00094 , values(NULL)
00095 , tag(-1)
00096 , flags(0)
00097 , distance(0.0)
00098 {
00099 }
00100
00101 void markValid(double d)
00102 {
00103 distance = d;
00104 flags |= GOAL_DISTANCE_KNOWN;
00105 markValid();
00106 }
00107
00108 void markValid()
00109 {
00110 flags |= (VALIDITY_KNOWN | VALIDITY_TRUE);
00111 }
00112
00113 void markInvalid(double d)
00114 {
00115 distance = d;
00116 flags |= GOAL_DISTANCE_KNOWN;
00117 markInvalid();
00118 }
00119
00120 void markInvalid()
00121 {
00122 flags &= ~VALIDITY_TRUE;
00123 flags |= VALIDITY_KNOWN;
00124 }
00125
00126 bool isValidityKnown() const
00127 {
00128 return flags & VALIDITY_KNOWN;
00129 }
00130
00131 void clearKnownInformation()
00132 {
00133 flags = 0;
00134 }
00135
00136 bool isMarkedValid() const
00137 {
00138 return flags & VALIDITY_TRUE;
00139 }
00140
00141 bool isGoalDistanceKnown() const
00142 {
00143 return flags & GOAL_DISTANCE_KNOWN;
00144 }
00145
00146 bool isStartState() const
00147 {
00148 return flags & IS_START_STATE;
00149 }
00150
00151 bool isGoalState() const
00152 {
00153 return flags & IS_GOAL_STATE;
00154 }
00155
00156 bool isInputState() const
00157 {
00158 return flags & (IS_START_STATE | IS_GOAL_STATE);
00159 }
00160
00161 void markStartState()
00162 {
00163 flags |= IS_START_STATE;
00164 }
00165
00166 void markGoalState()
00167 {
00168 flags |= IS_GOAL_STATE;
00169 }
00170
00171 double *values;
00172 int tag;
00173 int flags;
00174 double distance;
00175 };
00176
00177 ModelBasedStateSpace(const ModelBasedStateSpaceSpecification &spec);
00178 virtual ~ModelBasedStateSpace();
00179
00180 void setInterpolationFunction(const InterpolationFunction &fun)
00181 {
00182 interpolation_function_ = fun;
00183 }
00184
00185 void setDistanceFunction(const DistanceFunction &fun)
00186 {
00187 distance_function_ = fun;
00188 }
00189
00190 virtual ompl::base::State* allocState() const;
00191 virtual void freeState(ompl::base::State *state) const;
00192 virtual unsigned int getDimension() const;
00193 virtual void enforceBounds(ompl::base::State *state) const;
00194 virtual bool satisfiesBounds(const ompl::base::State *state) const;
00195
00196 virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const;
00197 virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const;
00198 virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const;
00199 virtual bool equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const;
00200 virtual double getMaximumExtent() const;
00201 virtual double getMeasure() const;
00202
00203 virtual unsigned int getSerializationLength() const;
00204 virtual void serialize(void *serialization, const ompl::base::State *state) const;
00205 virtual void deserialize(ompl::base::State *state, const void *serialization) const;
00206 virtual double* getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const;
00207
00208 virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const;
00209
00210
00211 const robot_model::RobotModelConstPtr& getRobotModel() const
00212 {
00213 return spec_.robot_model_;
00214 }
00215
00216 const robot_model::JointModelGroup* getJointModelGroup() const
00217 {
00218 return spec_.joint_model_group_;
00219 }
00220
00221 const std::string& getJointModelGroupName() const
00222 {
00223 return getJointModelGroup()->getName();
00224 }
00225
00226 const ModelBasedStateSpaceSpecification& getSpecification() const
00227 {
00228 return spec_;
00229 }
00230
00231 virtual void printState(const ompl::base::State *state, std::ostream &out) const;
00232 virtual void printSettings(std::ostream &out) const;
00233
00235 virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
00236
00237 const robot_model::JointBoundsVector& getJointsBounds() const
00238 {
00239 return spec_.joint_bounds_;
00240 }
00241
00243
00244 virtual void copyToRobotState(robot_state::RobotState &rstate, const ompl::base::State *state) const;
00245
00247
00248 virtual void copyToOMPLState(ompl::base::State *state, const robot_state::RobotState &rstate) const;
00249
00258 virtual void copyJointToOMPLState(ompl::base::State *state, const robot_state::RobotState &robot_state,
00259 const moveit::core::JointModel* joint_model, int ompl_state_joint_index) const;
00260
00261 double getTagSnapToSegment() const;
00262 void setTagSnapToSegment(double snap);
00263
00264 protected:
00265
00266 ModelBasedStateSpaceSpecification spec_;
00267 std::vector<robot_model::JointModel::Bounds> joint_bounds_storage_;
00268 std::vector<const robot_model::JointModel*> joint_model_vector_;
00269 unsigned int variable_count_;
00270 size_t state_values_size_;
00271
00272 InterpolationFunction interpolation_function_;
00273 DistanceFunction distance_function_;
00274
00275 double tag_snap_to_segment_;
00276 double tag_snap_to_segment_complement_;
00277
00278 };
00279
00280 typedef boost::shared_ptr<ModelBasedStateSpace> ModelBasedStateSpacePtr;
00281
00282 }
00283
00284 #endif