fix_start_state_collision.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
41 #include <ros/ros.h>
42 
44 {
46 {
47 public:
48  static const std::string DT_PARAM_NAME;
49  static const std::string JIGGLE_PARAM_NAME;
50  static const std::string ATTEMPTS_PARAM_NAME;
51 
53  {
54  if (!nh_.getParam(DT_PARAM_NAME, max_dt_offset_))
55  {
56  max_dt_offset_ = 0.5;
57  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was not set. Using default value: " << max_dt_offset_);
58  }
59  else
60  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was set to " << max_dt_offset_);
61 
62  if (!nh_.getParam(JIGGLE_PARAM_NAME, jiggle_fraction_))
63  {
64  jiggle_fraction_ = 0.02;
65  ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was not set. Using default value: " << jiggle_fraction_);
66  }
67  else
68  ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was set to " << jiggle_fraction_);
69 
70  if (!nh_.getParam(ATTEMPTS_PARAM_NAME, sampling_attempts_))
71  {
72  sampling_attempts_ = 100;
73  ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was not set. Using default value: " << sampling_attempts_);
74  }
75  else
76  {
77  if (sampling_attempts_ < 1)
78  {
80  ROS_WARN_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' needs to be at least 1.");
81  }
82  ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was set to " << sampling_attempts_);
83  }
84  }
85 
86  virtual std::string getDescription() const
87  {
88  return "Fix Start State In Collision";
89  }
90 
91  virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
94  std::vector<std::size_t>& added_path_index) const
95  {
96  ROS_DEBUG("Running '%s'", getDescription().c_str());
97 
98  // get the specified start state
99  robot_state::RobotState start_state = planning_scene->getCurrentState();
100  robot_state::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
101 
103  creq.group_name = req.group_name;
105  planning_scene->checkCollision(creq, cres, start_state);
106  if (cres.collision)
107  {
108  // Rerun in verbose mode
111  vcreq.verbose = true;
112  planning_scene->checkCollision(vcreq, vcres, start_state);
113 
114  if (creq.group_name.empty())
115  ROS_INFO("Start state appears to be in collision");
116  else
117  ROS_INFO_STREAM("Start state appears to be in collision with respect to group " << creq.group_name);
118 
119  robot_state::RobotStatePtr prefix_state(new robot_state::RobotState(start_state));
120  random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
121 
122  const std::vector<const robot_model::JointModel*>& jmodels =
123  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
124  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
125  planning_scene->getRobotModel()->getJointModels();
126 
127  bool found = false;
128  for (int c = 0; !found && c < sampling_attempts_; ++c)
129  {
130  for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
131  {
132  std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
133  const double* original_values = prefix_state->getJointPositions(jmodels[i]);
134  jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
135  jmodels[i]->getMaximumExtent() * jiggle_fraction_);
136  start_state.setJointPositions(jmodels[i], sampled_variable_values);
138  planning_scene->checkCollision(creq, cres, start_state);
139  if (!cres.collision)
140  {
141  found = true;
142  ROS_INFO("Found a valid state near the start state at distance %lf after %d attempts",
143  prefix_state->distance(start_state), c);
144  }
145  }
146  }
147 
148  if (found)
149  {
151  robot_state::robotStateToRobotStateMsg(start_state, req2.start_state);
152  bool solved = planner(planning_scene, req2, res);
153  if (solved && !res.trajectory_->empty())
154  {
155  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a
156  // prefix to the computed trajectory)
157  res.trajectory_->setWayPointDurationFromPrevious(
158  0, std::min(max_dt_offset_, res.trajectory_->getAverageSegmentDuration()));
159  res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
160  // we add a prefix point, so we need to bump any previously added index positions
161  for (std::size_t i = 0; i < added_path_index.size(); ++i)
162  added_path_index[i]++;
163  added_path_index.push_back(0);
164  }
165  return solved;
166  }
167  else
168  {
169  ROS_WARN("Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %u sampling "
170  "attempts). Passing the original planning request to the planner.",
171  jiggle_fraction_, sampling_attempts_);
172  return planner(planning_scene, req, res);
173  }
174  }
175  else
176  {
177  if (creq.group_name.empty())
178  ROS_DEBUG("Start state is valid");
179  else
180  ROS_DEBUG_STREAM("Start state is valid with respect to group " << creq.group_name);
181  return planner(planning_scene, req, res);
182  }
183  }
184 
185 private:
190 };
191 
192 const std::string FixStartStateCollision::DT_PARAM_NAME = "start_state_max_dt";
193 const std::string FixStartStateCollision::JIGGLE_PARAM_NAME = "jiggle_fraction";
194 const std::string FixStartStateCollision::ATTEMPTS_PARAM_NAME = "max_sampling_attempts";
195 }
196 
robot_trajectory::RobotTrajectoryPtr trajectory_
#define ROS_WARN(...)
#define ROS_INFO(...)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
moveit_msgs::MotionPlanRequest MotionPlanRequest
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateCollision, planning_request_adapter::PlanningRequestAdapter)
boost::function< bool(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res)> PlannerFn
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const
#define ROS_DEBUG(...)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:33