fix_start_state_collision.cpp
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 the 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 #include <moveit/planning_request_adapter/planning_request_adapter.h>
00038 #include <moveit/robot_state/conversions.h>
00039 #include <moveit/trajectory_processing/trajectory_tools.h>
00040 #include <class_loader/class_loader.h>
00041 #include <ros/ros.h>
00042 
00043 namespace default_planner_request_adapters
00044 {
00045 
00046 class FixStartStateCollision : public planning_request_adapter::PlanningRequestAdapter
00047 {
00048 public:
00049 
00050   static const std::string DT_PARAM_NAME;
00051   static const std::string JIGGLE_PARAM_NAME;
00052   static const std::string ATTEMPTS_PARAM_NAME;
00053 
00054   FixStartStateCollision() : planning_request_adapter::PlanningRequestAdapter(), nh_("~")
00055   {
00056     if (!nh_.getParam(DT_PARAM_NAME, max_dt_offset_))
00057     {
00058       max_dt_offset_ = 0.5;
00059       ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was not set. Using default value: " << max_dt_offset_);
00060     }
00061     else
00062       ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was set to " << max_dt_offset_);
00063 
00064     if (!nh_.getParam(JIGGLE_PARAM_NAME, jiggle_fraction_))
00065     {
00066       jiggle_fraction_ = 0.02;
00067       ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was not set. Using default value: " << jiggle_fraction_);
00068     }
00069     else
00070       ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was set to " << jiggle_fraction_);
00071 
00072     if (!nh_.getParam(ATTEMPTS_PARAM_NAME, sampling_attempts_))
00073     {
00074       sampling_attempts_ = 100;
00075       ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was not set. Using default value: " << sampling_attempts_);
00076     }
00077     else
00078     {
00079       if (sampling_attempts_ < 1)
00080       {
00081         sampling_attempts_ = 1;
00082         ROS_WARN_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' needs to be at least 1.");
00083       }
00084       ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was set to " << sampling_attempts_);
00085     }
00086 
00087   }
00088 
00089   virtual std::string getDescription() const { return "Fix Start State In Collision"; }
00090 
00091   virtual bool adaptAndPlan(const PlannerFn &planner,
00092                             const planning_scene::PlanningSceneConstPtr& planning_scene,
00093                             const planning_interface::MotionPlanRequest &req,
00094                             planning_interface::MotionPlanResponse &res,
00095                             std::vector<std::size_t> &added_path_index) const
00096   {
00097     ROS_DEBUG("Running '%s'", getDescription().c_str());
00098 
00099     // get the specified start state
00100     robot_state::RobotState start_state = planning_scene->getCurrentState();
00101     robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
00102 
00103     collision_detection::CollisionRequest creq;
00104     creq.group_name = req.group_name;
00105     collision_detection::CollisionResult cres;
00106     planning_scene->checkCollision(creq, cres, start_state);
00107     if (cres.collision)
00108     {
00109       // Rerun in verbose mode
00110       collision_detection::CollisionRequest vcreq = creq;
00111       collision_detection::CollisionResult vcres;
00112       vcreq.verbose = true;
00113       planning_scene->checkCollision(vcreq, vcres, start_state);
00114 
00115       if (creq.group_name.empty())
00116         ROS_INFO("Start state appears to be in collision");
00117       else
00118         ROS_INFO_STREAM("Start state appears to be in collision with respect to group " << creq.group_name);
00119 
00120       robot_state::RobotStatePtr prefix_state(new robot_state::RobotState(start_state));
00121       random_numbers::RandomNumberGenerator rng;
00122 
00123       const std::vector<robot_state::JointState*> &jstates =
00124         planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
00125         start_state.getJointStateGroup(req.group_name)->getJointStateVector() :
00126         start_state.getJointStateVector();
00127       bool found = false;
00128       for (int c = 0 ; !found && c < sampling_attempts_ ; ++c)
00129       {
00130         for (std::size_t i = 0 ; !found && i < jstates.size() ; ++i)
00131         {
00132           std::vector<double> sampled_variable_values;
00133           const std::vector<double> &original_values = prefix_state->getJointState(jstates[i]->getName())->getVariableValues();
00134           jstates[i]->getJointModel()->getVariableRandomValuesNearBy(rng, sampled_variable_values, jstates[i]->getVariableBounds(), original_values,
00135                                                                      jstates[i]->getJointModel()->getMaximumExtent() * jiggle_fraction_);
00136           jstates[i]->setVariableValues(sampled_variable_values);
00137           start_state.updateLinkTransforms();
00138           collision_detection::CollisionResult cres;
00139           planning_scene->checkCollision(creq, cres, start_state);
00140           if (!cres.collision)
00141           {
00142             found = true;
00143             ROS_INFO("Found a valid state near the start state at distance %lf after %d attempts", prefix_state->distance(start_state), c);
00144           }
00145         }
00146       }
00147 
00148       if (found)
00149       {
00150         planning_interface::MotionPlanRequest req2 = req;
00151         robot_state::robotStateToRobotStateMsg(start_state, req2.start_state);
00152         bool solved = planner(planning_scene, req2, res);
00153         if (solved && !res.trajectory_->empty())
00154         {
00155           // heuristically decide a duration offset for the trajectory (induced by the additional point added as a prefix to the computed trajectory)
00156           res.trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_, res.trajectory_->getAverageSegmentDuration()));
00157           res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
00158           added_path_index.push_back(0);
00159         }
00160         return solved;
00161       }
00162       else
00163       {
00164         ROS_WARN("Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %u sampling attempts). Passing the original planning request to the planner.",
00165                  jiggle_fraction_, sampling_attempts_);
00166         return planner(planning_scene, req, res);
00167       }
00168     }
00169     else
00170     {
00171       if (creq.group_name.empty())
00172         ROS_DEBUG("Start state is valid");
00173       else
00174         ROS_DEBUG_STREAM("Start state is valid with respect to group " << creq.group_name);
00175       return planner(planning_scene, req, res);
00176     }
00177   }
00178 
00179 private:
00180 
00181   ros::NodeHandle nh_;
00182   double max_dt_offset_;
00183   double jiggle_fraction_;
00184   int sampling_attempts_;
00185 };
00186 
00187 const std::string FixStartStateCollision::DT_PARAM_NAME = "start_state_max_dt";
00188 const std::string FixStartStateCollision::JIGGLE_PARAM_NAME = "jiggle_fraction";
00189 const std::string FixStartStateCollision::ATTEMPTS_PARAM_NAME = "max_sampling_attempts";
00190 
00191 }
00192 
00193 CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateCollision,
00194                             planning_request_adapter::PlanningRequestAdapter);


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:39