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


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