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 #include <moveit/ompl_interface/parameterization/model_based_state_space.h>
00038 #include <boost/bind.hpp>
00039
00040 ompl_interface::ModelBasedStateSpace::ModelBasedStateSpace(const ModelBasedStateSpaceSpecification &spec)
00041 : ompl::base::StateSpace()
00042 , spec_(spec)
00043 {
00044
00045 setName(spec_.joint_model_group_->getName());
00046 variable_count_ = spec_.joint_model_group_->getVariableCount();
00047 state_values_size_ = variable_count_ * sizeof(double);
00048 joint_model_vector_ = spec_.joint_model_group_->getActiveJointModels();
00049
00050
00051 if (!spec_.joint_bounds_.empty() && spec_.joint_bounds_.size() != joint_model_vector_.size())
00052 {
00053 logError("Joint group '%s' has incorrect bounds specified. Using the default bounds instead.", spec_.joint_model_group_->getName().c_str());
00054 spec_.joint_bounds_.clear();
00055 }
00056
00057
00058 if (spec_.joint_bounds_.empty())
00059 spec_.joint_bounds_ = spec_.joint_model_group_->getActiveJointModelsBounds();
00060
00061
00062
00063 joint_bounds_storage_.resize(spec_.joint_bounds_.size());
00064 for (std::size_t i = 0 ; i < joint_bounds_storage_.size() ; ++i)
00065 {
00066 joint_bounds_storage_[i] = *spec_.joint_bounds_[i];
00067 spec_.joint_bounds_[i] = &joint_bounds_storage_[i];
00068 }
00069
00070
00071 setTagSnapToSegment(0.95);
00072
00074 params_.declareParam<double>("tag_snap_to_segment",
00075 boost::bind(&ModelBasedStateSpace::setTagSnapToSegment, this, _1),
00076 boost::bind(&ModelBasedStateSpace::getTagSnapToSegment, this));
00077 }
00078
00079 ompl_interface::ModelBasedStateSpace::~ModelBasedStateSpace()
00080 {
00081 }
00082
00083 double ompl_interface::ModelBasedStateSpace::getTagSnapToSegment() const
00084 {
00085 return tag_snap_to_segment_;
00086 }
00087
00088 void ompl_interface::ModelBasedStateSpace::setTagSnapToSegment(double snap)
00089 {
00090 if (snap < 0.0 || snap > 1.0)
00091 logWarn("Snap to segment for tags is a ratio. It's value must be between 0.0 and 1.0. Value remains as previously set (%lf)", tag_snap_to_segment_);
00092 else
00093 {
00094 tag_snap_to_segment_ = snap;
00095 tag_snap_to_segment_complement_ = 1.0 - tag_snap_to_segment_;
00096 }
00097 }
00098
00099 ompl::base::State* ompl_interface::ModelBasedStateSpace::allocState() const
00100 {
00101 StateType *state = new StateType();
00102 state->values = new double[variable_count_];
00103 return state;
00104 }
00105
00106 void ompl_interface::ModelBasedStateSpace::freeState(ompl::base::State *state) const
00107 {
00108 delete[] state->as<StateType>()->values;
00109 delete state->as<StateType>();
00110 }
00111
00112 void ompl_interface::ModelBasedStateSpace::copyState(ompl::base::State *destination, const ompl::base::State *source) const
00113 {
00114 memcpy(destination->as<StateType>()->values, source->as<StateType>()->values, state_values_size_);
00115 destination->as<StateType>()->tag = source->as<StateType>()->tag;
00116 destination->as<StateType>()->flags = source->as<StateType>()->flags;
00117 destination->as<StateType>()->distance = source->as<StateType>()->distance;
00118 }
00119
00120 unsigned int ompl_interface::ModelBasedStateSpace::getSerializationLength() const
00121 {
00122 return state_values_size_ + sizeof(int);
00123 }
00124
00125 void ompl_interface::ModelBasedStateSpace::serialize(void *serialization, const ompl::base::State *state) const
00126 {
00127 *reinterpret_cast<int*>(serialization) = state->as<StateType>()->tag;
00128 memcpy(reinterpret_cast<char*>(serialization) + sizeof(int), state->as<StateType>()->values, state_values_size_);
00129 }
00130
00131 void ompl_interface::ModelBasedStateSpace::deserialize(ompl::base::State *state, const void *serialization) const
00132 {
00133 state->as<StateType>()->tag = *reinterpret_cast<const int*>(serialization);
00134 memcpy(state->as<StateType>()->values, reinterpret_cast<const char*>(serialization) + sizeof(int), state_values_size_);
00135 }
00136
00137 unsigned int ompl_interface::ModelBasedStateSpace::getDimension() const
00138 {
00139 unsigned int d = 0;
00140 for (std::size_t i = 0 ; i < joint_model_vector_.size() ; ++i)
00141 d += joint_model_vector_[i]->getStateSpaceDimension();
00142 return d;
00143 }
00144
00145 double ompl_interface::ModelBasedStateSpace::getMaximumExtent() const
00146 {
00147 return spec_.joint_model_group_->getMaximumExtent(spec_.joint_bounds_);
00148 }
00149
00150 double ompl_interface::ModelBasedStateSpace::getMeasure() const
00151 {
00152 double m = 1.0;
00153 for (std::size_t i = 0 ; i < spec_.joint_bounds_.size() ; ++i)
00154 {
00155 const robot_model::JointModel::Bounds& bounds = *spec_.joint_bounds_[i];
00156 for (std::size_t j = 0; j < bounds.size(); ++j)
00157 {
00158 m *= bounds[j].max_position_ - bounds[j].min_position_;
00159 }
00160 }
00161 return m;
00162 }
00163
00164 double ompl_interface::ModelBasedStateSpace::distance(const ompl::base::State *state1, const ompl::base::State *state2) const
00165 {
00166 if (distance_function_)
00167 return distance_function_(state1, state2);
00168 else
00169 return spec_.joint_model_group_->distance(state1->as<StateType>()->values, state2->as<StateType>()->values);
00170 }
00171
00172 bool ompl_interface::ModelBasedStateSpace::equalStates(const ompl::base::State *state1, const ompl::base::State *state2) const
00173 {
00174 for (unsigned int i = 0 ; i < variable_count_ ; ++i)
00175 if (fabs(state1->as<StateType>()->values[i] - state2->as<StateType>()->values[i]) > std::numeric_limits<double>::epsilon())
00176 return false;
00177 return true;
00178 }
00179
00180 void ompl_interface::ModelBasedStateSpace::enforceBounds(ompl::base::State *state) const
00181 {
00182 spec_.joint_model_group_->enforcePositionBounds(state->as<StateType>()->values, spec_.joint_bounds_);
00183 }
00184
00185 bool ompl_interface::ModelBasedStateSpace::satisfiesBounds(const ompl::base::State *state) const
00186 {
00187 return spec_.joint_model_group_->satisfiesPositionBounds(state->as<StateType>()->values, spec_.joint_bounds_, std::numeric_limits<double>::epsilon());
00188 }
00189
00190 void ompl_interface::ModelBasedStateSpace::interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
00191 {
00192
00193 state->as<StateType>()->clearKnownInformation();
00194
00195 if (!interpolation_function_ || !interpolation_function_(from, to, t, state))
00196 {
00197
00198 spec_.joint_model_group_->interpolate(from->as<StateType>()->values, to->as<StateType>()->values, t, state->as<StateType>()->values);
00199
00200
00201 if (from->as<StateType>()->tag >= 0 && t < 1.0 - tag_snap_to_segment_)
00202 state->as<StateType>()->tag = from->as<StateType>()->tag;
00203 else
00204 if (to->as<StateType>()->tag >= 0 && t > tag_snap_to_segment_)
00205 state->as<StateType>()->tag = to->as<StateType>()->tag;
00206 else
00207 state->as<StateType>()->tag = -1;
00208 }
00209 }
00210
00211 double* ompl_interface::ModelBasedStateSpace::getValueAddressAtIndex(ompl::base::State *state, const unsigned int index) const
00212 {
00213 if (index >= variable_count_)
00214 return NULL;
00215 return state->as<StateType>()->values + index;
00216 }
00217
00218 void ompl_interface::ModelBasedStateSpace::setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
00219 {
00220 for (std::size_t i = 0 ; i < joint_model_vector_.size() ; ++i)
00221 if (joint_model_vector_[i]->getType() == robot_model::JointModel::PLANAR)
00222 {
00223 joint_bounds_storage_[i][0].min_position_ = minX;
00224 joint_bounds_storage_[i][0].max_position_ = maxX;
00225 joint_bounds_storage_[i][1].min_position_ = minY;
00226 joint_bounds_storage_[i][1].max_position_ = maxY;
00227 }
00228 else
00229 if (joint_model_vector_[i]->getType() == robot_model::JointModel::FLOATING)
00230 {
00231 joint_bounds_storage_[i][0].min_position_ = minX;
00232 joint_bounds_storage_[i][0].max_position_ = maxX;
00233 joint_bounds_storage_[i][1].min_position_ = minY;
00234 joint_bounds_storage_[i][1].max_position_ = maxY;
00235 joint_bounds_storage_[i][2].min_position_ = minZ;
00236 joint_bounds_storage_[i][2].max_position_ = maxZ;
00237 }
00238 }
00239
00240 ompl::base::StateSamplerPtr ompl_interface::ModelBasedStateSpace::allocDefaultStateSampler() const
00241 {
00242 class DefaultStateSampler : public ompl::base::StateSampler
00243 {
00244 public:
00245
00246 DefaultStateSampler(const ompl::base::StateSpace *space,
00247 const robot_model::JointModelGroup *group,
00248 const robot_model::JointBoundsVector *joint_bounds)
00249 : ompl::base::StateSampler(space)
00250 , joint_model_group_(group)
00251 , joint_bounds_(joint_bounds)
00252 {
00253 }
00254
00255 virtual void sampleUniform(ompl::base::State *state)
00256 {
00257 joint_model_group_->getVariableRandomPositions(moveit_rng_, state->as<StateType>()->values, *joint_bounds_);
00258 state->as<StateType>()->clearKnownInformation();
00259 }
00260
00261 virtual void sampleUniformNear(ompl::base::State *state, const ompl::base::State *near, const double distance)
00262 {
00263 joint_model_group_->getVariableRandomPositionsNearBy(moveit_rng_, state->as<StateType>()->values, *joint_bounds_, near->as<StateType>()->values, distance);
00264 state->as<StateType>()->clearKnownInformation();
00265 }
00266
00267 virtual void sampleGaussian(ompl::base::State *state, const ompl::base::State *mean, const double stdDev)
00268 {
00269 sampleUniformNear(state, mean, rng_.gaussian(0.0, stdDev));
00270 }
00271
00272 protected:
00273
00274 random_numbers::RandomNumberGenerator moveit_rng_;
00275 const robot_model::JointModelGroup *joint_model_group_;
00276 const robot_model::JointBoundsVector *joint_bounds_;
00277 };
00278
00279 return ompl::base::StateSamplerPtr(static_cast<ompl::base::StateSampler*>
00280 (new DefaultStateSampler(this, spec_.joint_model_group_, &spec_.joint_bounds_)));
00281 }
00282
00283 void ompl_interface::ModelBasedStateSpace::printSettings(std::ostream &out) const
00284 {
00285 out << "ModelBasedStateSpace '" << getName() << "' at " << this << std::endl;
00286 }
00287
00288 void ompl_interface::ModelBasedStateSpace::printState(const ompl::base::State *state, std::ostream &out) const
00289 {
00290 for (std::size_t j = 0 ; j < joint_model_vector_.size() ; ++j)
00291 {
00292 out << joint_model_vector_[j]->getName() << " = ";
00293 const int idx = spec_.joint_model_group_->getVariableGroupIndex(joint_model_vector_[j]->getName());
00294 const int vc = joint_model_vector_[j]->getVariableCount();
00295 for (int i = 0 ; i < vc ; ++i)
00296 out << state->as<StateType>()->values[idx + i] << " ";
00297 out << std::endl;
00298 }
00299
00300 if (state->as<StateType>()->isStartState())
00301 out << "* start state" << std::endl;
00302 if (state->as<StateType>()->isGoalState())
00303 out << "* goal state" << std::endl;
00304 if (state->as<StateType>()->isValidityKnown())
00305 {
00306 if (state->as<StateType>()->isMarkedValid())
00307 out << "* valid state" << std::endl;
00308 else
00309 out << "* invalid state" << std::endl;
00310 }
00311 out << "Tag: " << state->as<StateType>()->tag << std::endl;
00312 }
00313
00314 void ompl_interface::ModelBasedStateSpace::copyToRobotState(robot_state::RobotState& rstate, const ompl::base::State *state) const
00315 {
00316 rstate.setJointGroupPositions(spec_.joint_model_group_, state->as<StateType>()->values);
00317 rstate.update();
00318 }
00319
00320 void ompl_interface::ModelBasedStateSpace::copyToOMPLState(ompl::base::State *state, const robot_state::RobotState &rstate) const
00321 {
00322 rstate.copyJointGroupPositions(spec_.joint_model_group_, state->as<StateType>()->values);
00323
00324 state->as<StateType>()->clearKnownInformation();
00325 }
00326
00327 void ompl_interface::ModelBasedStateSpace::copyJointToOMPLState(ompl::base::State *state, const robot_state::RobotState &robot_state,
00328 const moveit::core::JointModel* joint_model, int ompl_state_joint_index) const
00329 {
00330
00331 memcpy(getValueAddressAtIndex(state, ompl_state_joint_index),
00332 robot_state.getVariablePositions() + joint_model->getFirstVariableIndex() * sizeof(double),
00333 joint_model->getVariableCount() * sizeof(double));
00334
00335
00336 state->as<StateType>()->clearKnownInformation();
00337 }