model_based_state_space.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
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 #include "../detail/same_shared_ptr.hpp"
00046 
00047 namespace ompl_interface
00048 {
00049 typedef boost::function<bool(const ompl::base::State* from, const ompl::base::State* to, const double t,
00050                              ompl::base::State* state)>
00051     InterpolationFunction;
00052 typedef boost::function<double(const ompl::base::State* state1, const ompl::base::State* state2)> DistanceFunction;
00053 
00054 struct ModelBasedStateSpaceSpecification
00055 {
00056   ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr& robot_model,
00057                                     const robot_model::JointModelGroup* jmg)
00058     : robot_model_(robot_model), joint_model_group_(jmg)
00059   {
00060   }
00061 
00062   ModelBasedStateSpaceSpecification(const robot_model::RobotModelConstPtr& robot_model, const std::string& group_name)
00063     : robot_model_(robot_model), joint_model_group_(robot_model_->getJointModelGroup(group_name))
00064   {
00065     if (!joint_model_group_)
00066       throw std::runtime_error("Group '" + group_name + "'  was not found");
00067   }
00068 
00069   robot_model::RobotModelConstPtr robot_model_;
00070   const robot_model::JointModelGroup* joint_model_group_;
00071   robot_model::JointBoundsVector joint_bounds_;
00072 };
00073 
00074 class ModelBasedStateSpace : public ompl::base::StateSpace
00075 {
00076 public:
00077   class StateType : public ompl::base::State
00078   {
00079   public:
00080     enum
00081     {
00082       VALIDITY_KNOWN = 1,
00083       GOAL_DISTANCE_KNOWN = 2,
00084       VALIDITY_TRUE = 4,
00085       IS_START_STATE = 8,
00086       IS_GOAL_STATE = 16
00087     };
00088 
00089     StateType() : ompl::base::State(), values(NULL), tag(-1), flags(0), distance(0.0)
00090     {
00091     }
00092 
00093     void markValid(double d)
00094     {
00095       distance = d;
00096       flags |= GOAL_DISTANCE_KNOWN;
00097       markValid();
00098     }
00099 
00100     void markValid()
00101     {
00102       flags |= (VALIDITY_KNOWN | VALIDITY_TRUE);
00103     }
00104 
00105     void markInvalid(double d)
00106     {
00107       distance = d;
00108       flags |= GOAL_DISTANCE_KNOWN;
00109       markInvalid();
00110     }
00111 
00112     void markInvalid()
00113     {
00114       flags &= ~VALIDITY_TRUE;
00115       flags |= VALIDITY_KNOWN;
00116     }
00117 
00118     bool isValidityKnown() const
00119     {
00120       return flags & VALIDITY_KNOWN;
00121     }
00122 
00123     void clearKnownInformation()
00124     {
00125       flags = 0;
00126     }
00127 
00128     bool isMarkedValid() const
00129     {
00130       return flags & VALIDITY_TRUE;
00131     }
00132 
00133     bool isGoalDistanceKnown() const
00134     {
00135       return flags & GOAL_DISTANCE_KNOWN;
00136     }
00137 
00138     bool isStartState() const
00139     {
00140       return flags & IS_START_STATE;
00141     }
00142 
00143     bool isGoalState() const
00144     {
00145       return flags & IS_GOAL_STATE;
00146     }
00147 
00148     bool isInputState() const
00149     {
00150       return flags & (IS_START_STATE | IS_GOAL_STATE);
00151     }
00152 
00153     void markStartState()
00154     {
00155       flags |= IS_START_STATE;
00156     }
00157 
00158     void markGoalState()
00159     {
00160       flags |= IS_GOAL_STATE;
00161     }
00162 
00163     double* values;
00164     int tag;
00165     int flags;
00166     double distance;
00167   };
00168 
00169   ModelBasedStateSpace(const ModelBasedStateSpaceSpecification& spec);
00170   virtual ~ModelBasedStateSpace();
00171 
00172   void setInterpolationFunction(const InterpolationFunction& fun)
00173   {
00174     interpolation_function_ = fun;
00175   }
00176 
00177   void setDistanceFunction(const DistanceFunction& fun)
00178   {
00179     distance_function_ = fun;
00180   }
00181 
00182   virtual ompl::base::State* allocState() const;
00183   virtual void freeState(ompl::base::State* state) const;
00184   virtual unsigned int getDimension() const;
00185   virtual void enforceBounds(ompl::base::State* state) const;
00186   virtual bool satisfiesBounds(const ompl::base::State* state) const;
00187 
00188   virtual void copyState(ompl::base::State* destination, const ompl::base::State* source) const;
00189   virtual void interpolate(const ompl::base::State* from, const ompl::base::State* to, const double t,
00190                            ompl::base::State* state) const;
00191   virtual double distance(const ompl::base::State* state1, const ompl::base::State* state2) const;
00192   virtual bool equalStates(const ompl::base::State* state1, const ompl::base::State* state2) const;
00193   virtual double getMaximumExtent() const;
00194   virtual double getMeasure() const;
00195 
00196   virtual unsigned int getSerializationLength() const;
00197   virtual void serialize(void* serialization, const ompl::base::State* state) const;
00198   virtual void deserialize(ompl::base::State* state, const void* serialization) const;
00199   virtual double* getValueAddressAtIndex(ompl::base::State* state, const unsigned int index) const;
00200 
00201   virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const;
00202 
00203   const robot_model::RobotModelConstPtr& getRobotModel() const
00204   {
00205     return spec_.robot_model_;
00206   }
00207 
00208   const robot_model::JointModelGroup* getJointModelGroup() const
00209   {
00210     return spec_.joint_model_group_;
00211   }
00212 
00213   const std::string& getJointModelGroupName() const
00214   {
00215     return getJointModelGroup()->getName();
00216   }
00217 
00218   const ModelBasedStateSpaceSpecification& getSpecification() const
00219   {
00220     return spec_;
00221   }
00222 
00223   virtual void printState(const ompl::base::State* state, std::ostream& out) const;
00224   virtual void printSettings(std::ostream& out) const;
00225 
00227   virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
00228 
00229   const robot_model::JointBoundsVector& getJointsBounds() const
00230   {
00231     return spec_.joint_bounds_;
00232   }
00233 
00235   // The joint states \b must be specified in the same order as the joint models in the constructor
00236   virtual void copyToRobotState(robot_state::RobotState& rstate, const ompl::base::State* state) const;
00237 
00239   //  The joint states \b must be specified in the same order as the joint models in the constructor
00240   virtual void copyToOMPLState(ompl::base::State* state, const robot_state::RobotState& rstate) const;
00241 
00252   virtual void copyJointToOMPLState(ompl::base::State* state, const robot_state::RobotState& robot_state,
00253                                     const moveit::core::JointModel* joint_model, int ompl_state_joint_index) const;
00254 
00255   double getTagSnapToSegment() const;
00256   void setTagSnapToSegment(double snap);
00257 
00258 protected:
00259   ModelBasedStateSpaceSpecification spec_;
00260   std::vector<robot_model::JointModel::Bounds> joint_bounds_storage_;
00261   std::vector<const robot_model::JointModel*> joint_model_vector_;
00262   unsigned int variable_count_;
00263   size_t state_values_size_;
00264 
00265   InterpolationFunction interpolation_function_;
00266   DistanceFunction distance_function_;
00267 
00268   double tag_snap_to_segment_;
00269   double tag_snap_to_segment_complement_;
00270 };
00271 
00272 typedef same_shared_ptr<ModelBasedStateSpace, ompl::base::StateSpacePtr>::type ModelBasedStateSpacePtr;
00273 }
00274 
00275 #endif


ompl
Author(s): Ioan Sucan
autogenerated on Mon Jul 24 2017 02:21:33