moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
40 #include <class_loader/class_loader.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/node.hpp>
44 #include <rclcpp/parameter_value.hpp>
45 
47 {
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros.fix_start_state_collision");
49 
51 {
52 public:
53  static const std::string DT_PARAM_NAME;
54  static const std::string JIGGLE_PARAM_NAME;
55  static const std::string ATTEMPTS_PARAM_NAME;
56 
57  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
58  {
59  node_ = node;
60  max_dt_offset_ = getParam(node_, LOGGER, parameter_namespace, DT_PARAM_NAME, 0.5);
61  jiggle_fraction_ = getParam(node_, LOGGER, parameter_namespace, JIGGLE_PARAM_NAME, 0.02);
62  sampling_attempts_ = getParam(node_, LOGGER, parameter_namespace, ATTEMPTS_PARAM_NAME, 100);
63  if (sampling_attempts_ < 1)
64  {
65  sampling_attempts_ = 1;
66  RCLCPP_WARN(LOGGER, "Param '%s' needs to be at least 1.", ATTEMPTS_PARAM_NAME.c_str());
67  }
68  }
69 
70  std::string getDescription() const override
71  {
72  return "Fix Start State In Collision";
73  }
74 
75  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
77  std::vector<std::size_t>& added_path_index) const override
78  {
79  RCLCPP_DEBUG(LOGGER, "Running '%s'", getDescription().c_str());
80 
81  // get the specified start state
82  moveit::core::RobotState start_state = planning_scene->getCurrentState();
83  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
84 
86  creq.group_name = req.group_name;
88  planning_scene->checkCollision(creq, cres, start_state);
89  if (cres.collision)
90  {
91  // Rerun in verbose mode
94  vcreq.verbose = true;
95  planning_scene->checkCollision(vcreq, vcres, start_state);
96 
97  if (creq.group_name.empty())
98  RCLCPP_INFO(LOGGER, "Start state appears to be in collision");
99  else
100  RCLCPP_INFO(LOGGER, "Start state appears to be in collision with respect to group %s", creq.group_name.c_str());
101 
102  auto prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
103  random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
104 
105  const std::vector<const moveit::core::JointModel*>& jmodels =
106  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
107  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
108  planning_scene->getRobotModel()->getJointModels();
109 
110  bool found = false;
111  for (int c = 0; !found && c < sampling_attempts_; ++c)
112  {
113  for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
114  {
115  std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
116  const double* original_values = prefix_state->getJointPositions(jmodels[i]);
117  jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
118  jmodels[i]->getMaximumExtent() * jiggle_fraction_);
119  start_state.setJointPositions(jmodels[i], sampled_variable_values);
121  planning_scene->checkCollision(creq, cres, start_state);
122  if (!cres.collision)
123  {
124  found = true;
125  RCLCPP_INFO(LOGGER, "Found a valid state near the start state at distance %lf after %d attempts",
126  prefix_state->distance(start_state), c);
127  }
128  }
129  }
130 
131  if (found)
132  {
134  moveit::core::robotStateToRobotStateMsg(start_state, req2.start_state);
135  bool solved = planner(planning_scene, req2, res);
136  if (solved && !res.trajectory_->empty())
137  {
138  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a
139  // prefix to the computed trajectory)
140  res.trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_,
141  res.trajectory_->getAverageSegmentDuration()));
142  res.trajectory_->addPrefixWayPoint(prefix_state, 0.0);
143  // we add a prefix point, so we need to bump any previously added index positions
144  for (std::size_t& added_index : added_path_index)
145  added_index++;
146  added_path_index.push_back(0);
147  }
148  return solved;
149  }
150  else
151  {
152  RCLCPP_WARN(LOGGER,
153  "Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %u sampling "
154  "attempts). Passing the original planning request to the planner.",
155  jiggle_fraction_, sampling_attempts_);
156  return planner(planning_scene, req, res);
157  }
158  }
159  else
160  {
161  if (creq.group_name.empty())
162  RCLCPP_DEBUG(LOGGER, "Start state is valid");
163  else
164  RCLCPP_DEBUG(LOGGER, "Start state is valid with respect to group %s", creq.group_name.c_str());
165  return planner(planning_scene, req, res);
166  }
167  }
168 
169 private:
170  rclcpp::Node::SharedPtr node_;
171  double max_dt_offset_;
172  double jiggle_fraction_;
173  int sampling_attempts_;
174 };
175 
176 const std::string FixStartStateCollision::DT_PARAM_NAME = "start_state_max_dt";
177 const std::string FixStartStateCollision::JIGGLE_PARAM_NAME = "jiggle_fraction";
178 const std::string FixStartStateCollision::ATTEMPTS_PARAM_NAME = "max_sampling_attempts";
179 } // namespace default_planner_request_adapters
180 
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
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
Adapt the planning request if needed, call the planner function planner and update the planning respo...
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setJointPositions(const std::string &joint_name, const double *position)
Definition: robot_state.h:515
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string &parameter_namespace, const std::string &parameter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)