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 {
45 class FixStartStateCollision : public planning_request_adapter::PlanningRequestAdapter
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  }
55 
56  void initialize(const ros::NodeHandle& nh) override
57  {
59  {
60  max_dt_offset_ = 0.5;
61  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was not set. Using default value: " << max_dt_offset_);
62  }
63  else
64  ROS_INFO_STREAM("Param '" << DT_PARAM_NAME << "' was set to " << max_dt_offset_);
65 
67  {
68  jiggle_fraction_ = 0.02;
69  ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was not set. Using default value: " << jiggle_fraction_);
70  }
71  else
72  ROS_INFO_STREAM("Param '" << JIGGLE_PARAM_NAME << "' was set to " << jiggle_fraction_);
73 
75  {
76  sampling_attempts_ = 100;
77  ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was not set. Using default value: " << sampling_attempts_);
78  }
79  else
80  {
81  if (sampling_attempts_ < 1)
82  {
84  ROS_WARN_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' needs to be at least 1.");
85  }
86  ROS_INFO_STREAM("Param '" << ATTEMPTS_PARAM_NAME << "' was set to " << sampling_attempts_);
87  }
88  }
89 
90  std::string getDescription() const override
91  {
92  return "Fix Start State In Collision";
93  }
94 
95  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
97  std::vector<std::size_t>& added_path_index) const override
98  {
99  ROS_DEBUG("Running '%s'", getDescription().c_str());
100 
101  // get the specified start state
102  moveit::core::RobotState start_state = planning_scene->getCurrentState();
103  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
104 
106  creq.group_name = req.group_name;
108  planning_scene->checkCollision(creq, cres, start_state);
109  if (cres.collision)
110  {
111  // Rerun in verbose mode
114  vcreq.verbose = true;
115  planning_scene->checkCollision(vcreq, vcres, start_state);
116 
117  if (creq.group_name.empty())
118  ROS_INFO("Start state appears to be in collision");
119  else
120  ROS_INFO_STREAM("Start state appears to be in collision with respect to group " << creq.group_name);
121 
122  moveit::core::RobotStatePtr prefix_state(new moveit::core::RobotState(start_state));
123  random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
124 
125  const std::vector<const moveit::core::JointModel*>& jmodels =
126  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
127  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
128  planning_scene->getRobotModel()->getJointModels();
129 
130  bool found = false;
131  for (int c = 0; !found && c < sampling_attempts_; ++c)
132  {
133  for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
134  {
135  std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
136  const double* original_values = prefix_state->getJointPositions(jmodels[i]);
137  jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
138  jmodels[i]->getMaximumExtent() * jiggle_fraction_);
139  start_state.setJointPositions(jmodels[i], sampled_variable_values);
141  planning_scene->checkCollision(creq, cres, start_state);
142  if (!cres.collision)
143  {
144  found = true;
145  ROS_INFO("Found a valid state near the start state at distance %lf after %d attempts",
146  prefix_state->distance(start_state), c);
147  }
148  }
149  }
150 
151  if (found)
152  {
154  moveit::core::robotStateToRobotStateMsg(start_state, req2.start_state);
155  bool solved = planner(planning_scene, req2, res);
156  if (solved && !res.trajectory_->empty())
157  {
158  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a
159  // prefix to the computed trajectory)
160  res.trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_,
161  res.trajectory_->getAverageSegmentDuration()));
162  res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
163  // we add a prefix point, so we need to bump any previously added index positions
164  for (std::size_t& added_index : added_path_index)
165  added_index++;
166  added_path_index.push_back(0);
167  }
168  return solved;
169  }
170  else
171  {
172  ROS_WARN("Unable to find a valid state nearby the start state "
173  "(using jiggle fraction of %lf and %u sampling attempts).",
175  res.error_code_.val = moveit_msgs::MoveItErrorCodes::START_STATE_IN_COLLISION;
176  return false;
177  }
178  }
179  else
180  {
181  if (creq.group_name.empty())
182  ROS_DEBUG("Start state is valid");
183  else
184  ROS_DEBUG_STREAM("Start state is valid with respect to group " << creq.group_name);
185  return planner(planning_scene, req, res);
186  }
187  }
188 
189 private:
190  double max_dt_offset_;
191  double jiggle_fraction_;
192  int sampling_attempts_;
193 };
194 
195 const std::string FixStartStateCollision::DT_PARAM_NAME = "start_state_max_dt";
196 const std::string FixStartStateCollision::JIGGLE_PARAM_NAME = "jiggle_fraction";
197 const std::string FixStartStateCollision::ATTEMPTS_PARAM_NAME = "max_sampling_attempts";
198 } // namespace default_planner_request_adapters
199 
moveit::core::RobotState::setJointPositions
void setJointPositions(const std::string &joint_name, const double *position)
default_planner_request_adapters::FixStartStateCollision::ATTEMPTS_PARAM_NAME
static const std::string ATTEMPTS_PARAM_NAME
Definition: fix_start_state_collision.cpp:114
planning_interface::MotionPlanResponse
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
planning_request_adapter.h
ros.h
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
ROS_DEBUG
#define ROS_DEBUG(...)
default_planner_request_adapters::FixStartStateCollision::sampling_attempts_
int sampling_attempts_
Definition: fix_start_state_collision.cpp:256
default_planner_request_adapters::FixStartStateCollision::getDescription
std::string getDescription() const override
Definition: fix_start_state_collision.cpp:154
moveit::core::RobotState
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
collision_detection::CollisionRequest
planning_request_adapter::PlanningRequestAdapter
default_planner_request_adapters::FixStartStateCollision::initialize
void initialize(const ros::NodeHandle &nh) override
Definition: fix_start_state_collision.cpp:120
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
CLASS_LOADER_REGISTER_CLASS
CLASS_LOADER_REGISTER_CLASS(default_planner_request_adapters::FixStartStateCollision, planning_request_adapter::PlanningRequestAdapter)
default_planner_request_adapters::FixStartStateCollision::max_dt_offset_
double max_dt_offset_
Definition: fix_start_state_collision.cpp:254
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
collision_detection::CollisionResult
collision_detection::CollisionRequest::verbose
bool verbose
collision_detection::CollisionRequest::group_name
std::string group_name
default_planner_request_adapters::FixStartStateCollision::jiggle_fraction_
double jiggle_fraction_
Definition: fix_start_state_collision.cpp:255
default_planner_request_adapters::FixStartStateCollision::JIGGLE_PARAM_NAME
static const std::string JIGGLE_PARAM_NAME
Definition: fix_start_state_collision.cpp:113
ROS_WARN
#define ROS_WARN(...)
class_loader.hpp
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
default_planner_request_adapters::FixStartStateCollision::adaptAndPlan
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 override
Definition: fix_start_state_collision.cpp:159
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
random_numbers::RandomNumberGenerator
default_planner_request_adapters::FixStartStateCollision::FixStartStateCollision
FixStartStateCollision()
Definition: fix_start_state_collision.cpp:116
planning_request_adapter::PlanningRequestAdapter::PlanningRequestAdapter
PlanningRequestAdapter()
default_planner_request_adapters
Definition: add_iterative_spline_parameterization.cpp:43
default_planner_request_adapters::FixStartStateCollision::DT_PARAM_NAME
static const std::string DT_PARAM_NAME
Definition: fix_start_state_collision.cpp:112
planning_request_adapter::PlanningRequestAdapter::PlannerFn
boost::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
default_planner_request_adapters::FixStartStateCollision
Definition: fix_start_state_collision.cpp:77
planning_request_adapter
collision_detection::CollisionResult::collision
bool collision
conversions.h
trajectory_tools.h
ROS_INFO
#define ROS_INFO(...)
planning_scene
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ros::NodeHandle
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03