default_constraint_samplers.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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_CONSTRAINT_SAMPLERS_DEFAULT_CONSTRAINT_SAMPLERS_
00038 #define MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_CONSTRAINT_SAMPLERS_
00039 
00040 #include <moveit/constraint_samplers/constraint_sampler.h>
00041 #include <random_numbers/random_numbers.h>
00042 
00043 namespace constraint_samplers
00044 {
00045 
00055 class JointConstraintSampler : public ConstraintSampler
00056 {
00057 public:
00058 
00069   JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene,
00070                          const std::string &group_name) :
00071     ConstraintSampler(scene, group_name)
00072   {
00073   }
00091   virtual bool configure(const moveit_msgs::Constraints &constr);
00092 
00118   bool configure(const std::vector<kinematic_constraints::JointConstraint> &jc);
00119 
00120   virtual bool sample(robot_state::RobotState &state,
00121                       const robot_state::RobotState &ks,
00122                       unsigned int max_attempts);
00123 
00124   virtual bool project(robot_state::RobotState &state,
00125                        unsigned int max_attempts);
00126 
00134   std::size_t getConstrainedJointCount() const
00135   {
00136     return bounds_.size();
00137   }
00138 
00145   std::size_t getUnconstrainedJointCount() const
00146   {
00147     return unbounded_.size();
00148   }
00149 
00155   virtual const std::string& getName() const
00156   {
00157     static const std::string SAMPLER_NAME = "JointConstraintSampler";
00158     return SAMPLER_NAME;
00159   }
00160 
00161 protected:
00162 
00164   struct JointInfo
00165   {
00171     JointInfo()
00172     {
00173       min_bound_ = -std::numeric_limits<double>::max();
00174       max_bound_ = std::numeric_limits<double>::max();
00175     }
00176 
00186     void potentiallyAdjustMinMaxBounds(double min, double max)
00187     {
00188       min_bound_ = std::max(min, min_bound_);
00189       max_bound_ = std::min(max, max_bound_);
00190     }
00191 
00192     double min_bound_;          
00193     double max_bound_;          
00194     std::size_t index_;         
00195   };
00196 
00197   virtual void clear();
00198 
00199   random_numbers::RandomNumberGenerator           random_number_generator_; 
00200   std::vector<JointInfo>                          bounds_; 
00202   std::vector<const robot_model::JointModel*> unbounded_; 
00203   std::vector<unsigned int>                       uindex_; 
00204   std::vector<double>                             values_; 
00205 };
00206 
00212 struct IKSamplingPose
00213 {
00219   IKSamplingPose();
00220 
00227   IKSamplingPose(const kinematic_constraints::PositionConstraint &pc);
00228 
00236   IKSamplingPose(const kinematic_constraints::OrientationConstraint &oc);
00237 
00247   IKSamplingPose(const kinematic_constraints::PositionConstraint &pc,
00248                  const kinematic_constraints::OrientationConstraint &oc);
00249 
00257   IKSamplingPose(const boost::shared_ptr<kinematic_constraints::PositionConstraint> &pc);
00258 
00266   IKSamplingPose(const boost::shared_ptr<kinematic_constraints::OrientationConstraint> &oc);
00267 
00268 
00277   IKSamplingPose(const boost::shared_ptr<kinematic_constraints::PositionConstraint> &pc,
00278                  const boost::shared_ptr<kinematic_constraints::OrientationConstraint> &oc);
00279 
00280   boost::shared_ptr<kinematic_constraints::PositionConstraint>    position_constraint_; 
00281   boost::shared_ptr<kinematic_constraints::OrientationConstraint> orientation_constraint_; 
00282 };
00283 
00293 class IKConstraintSampler : public ConstraintSampler
00294 {
00295 public:
00296 
00307   IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene,
00308                       const std::string &group_name) :
00309     ConstraintSampler(scene, group_name)
00310   {
00311   }
00312 
00337   virtual bool configure(const moveit_msgs::Constraints &constr);
00338 
00363   bool configure(const IKSamplingPose &sp);
00364 
00371   double getIKTimeout() const
00372   {
00373     return ik_timeout_;
00374   }
00375 
00381   void setIKTimeout(double timeout)
00382   {
00383     ik_timeout_ = timeout;
00384   }
00385 
00392   const boost::shared_ptr<kinematic_constraints::PositionConstraint>& getPositionConstraint() const
00393   {
00394     return sampling_pose_.position_constraint_;
00395   }
00402   const boost::shared_ptr<kinematic_constraints::OrientationConstraint>& getOrientationConstraint() const
00403   {
00404     return sampling_pose_.orientation_constraint_;
00405   }
00406 
00420   double getSamplingVolume() const;
00421 
00428   const std::string& getLinkName() const;
00429 
00451   virtual bool sample(robot_state::RobotState &state,
00452                       const robot_state::RobotState &reference_state,
00453                       unsigned int max_attempts);
00454 
00455   virtual bool project(robot_state::RobotState &state,
00456                        unsigned int max_attempts);
00479   bool samplePose(Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const robot_state::RobotState &ks, unsigned int max_attempts);
00480 
00486   virtual const std::string& getName() const
00487   {
00488     static const std::string SAMPLER_NAME = "IKConstraintSampler";
00489     return SAMPLER_NAME;
00490   }
00491 
00492 protected:
00493 
00494   virtual void clear();
00495 
00501   bool loadIKSolver();
00502 
00513   bool callIK(const geometry_msgs::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback,
00514               double timeout, robot_state::RobotState &state, bool use_as_seed);
00515   bool sampleHelper(robot_state::RobotState &state, const robot_state::RobotState &reference_state, unsigned int max_attempts, bool project);
00516   bool validate(robot_state::RobotState &state) const;
00517 
00518   random_numbers::RandomNumberGenerator random_number_generator_; 
00519   IKSamplingPose                        sampling_pose_; 
00520   kinematics::KinematicsBaseConstPtr    kb_; 
00521   double                                ik_timeout_; 
00522   std::string                           ik_frame_; 
00523   bool                                  transform_ik_; 
00524 };
00525 
00526 
00527 }
00528 
00529 
00530 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:52