pose_model_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_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 #include <ompl/base/spaces/SE3StateSpace.h>
00042 
00043 namespace ompl_interface
00044 {
00045 
00046 class PoseModelStateSpace : public ModelBasedStateSpace
00047 {
00048 public:
00049 
00050   static const std::string PARAMETERIZATION_TYPE;
00051 
00052   class StateType : public ModelBasedStateSpace::StateType
00053   {
00054   public:
00055     enum
00056       {
00057         JOINTS_COMPUTED = 256,
00058         POSE_COMPUTED = 512
00059       };
00060     
00061     StateType() 
00062       : ModelBasedStateSpace::StateType()
00063       , poses(NULL)
00064     {
00065       flags |= JOINTS_COMPUTED;
00066     }
00067     
00068     bool jointsComputed() const
00069     {
00070       return flags & JOINTS_COMPUTED;
00071     }
00072     
00073     bool poseComputed() const
00074     {
00075       return flags & POSE_COMPUTED;
00076     }
00077     
00078     void setJointsComputed(bool value)
00079     {
00080       if (value)
00081         flags |= JOINTS_COMPUTED;
00082       else
00083         flags &= ~JOINTS_COMPUTED;
00084     }
00085     
00086     void setPoseComputed(bool value)
00087     {
00088       if (value)
00089         flags |= POSE_COMPUTED;
00090       else
00091         flags &= ~POSE_COMPUTED;
00092     }
00093     
00094     ompl::base::SE3StateSpace::StateType **poses;
00095   };
00096   
00097   PoseModelStateSpace(const ModelBasedStateSpaceSpecification &spec);
00098   virtual ~PoseModelStateSpace();
00099   
00100   virtual ompl::base::State* allocState() const;
00101   virtual void freeState(ompl::base::State *state) const;
00102   virtual void copyState(ompl::base::State *destination, const ompl::base::State *source) const;
00103   virtual void interpolate(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const;
00104   virtual double distance(const ompl::base::State *state1, const ompl::base::State *state2) const;
00105   virtual double getMaximumExtent() const;
00106 
00107   virtual ompl::base::StateSamplerPtr allocDefaultStateSampler() const;
00108   
00109   bool computeStateFK(ompl::base::State *state) const;
00110   bool computeStateIK(ompl::base::State *state) const;
00111   bool computeStateK(ompl::base::State *state) const;
00112 
00113   virtual void setPlanningVolume(double minX, double maxX, double minY, double maxY, double minZ, double maxZ);
00114   virtual void copyToOMPLState(ompl::base::State *state, const robot_state::RobotState &rstate) const;
00115   virtual void sanityChecks() const;
00116 
00117 private:
00118 
00119   struct PoseComponent
00120   {
00121     PoseComponent(const robot_model::JointModelGroup *subgroup,
00122                   const robot_model::JointModelGroup::KinematicsSolver &k);
00123 
00124     bool computeStateFK(StateType *full_state, unsigned int idx) const;
00125     bool computeStateIK(StateType *full_state, unsigned int idx) const;
00126     
00127     bool operator<(const PoseComponent &o) const
00128     {
00129       return subgroup_->getName() < o.subgroup_->getName();
00130     }
00131     
00132     const robot_model::JointModelGroup *subgroup_;
00133     boost::shared_ptr<kinematics::KinematicsBase> kinematics_solver_;
00134     std::vector<unsigned int> bijection_;
00135     ompl::base::StateSpacePtr state_space_;
00136     std::vector<std::string> fk_link_;
00137   };
00138   
00139   std::vector<PoseComponent> poses_;
00140   double jump_factor_;
00141 };
00142 
00143 }
00144 
00145 #endif


ompl
Author(s): Ioan Sucan
autogenerated on Wed Sep 16 2015 04:42:27