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  * Desc: Fix start state collision adapter which will attempt to sample a new collision-free configuration near a
37  * specified configuration (in collision) by perturbing the joint values by a small amount. The amount that it will
38  * perturb the values by is specified by the jiggle_fraction parameter that controls the perturbation as a percentage of
39  * the total range of motion for the joint. The other parameter for this adapter specifies how many random perturbations
40  * the adapter will sample before giving up.
41  */
42 
46 #include <class_loader/class_loader.hpp>
47 #include <rclcpp/logger.hpp>
48 #include <rclcpp/logging.hpp>
49 #include <rclcpp/node.hpp>
50 #include <rclcpp/parameter_value.hpp>
51 #include <moveit/utils/logger.hpp>
52 
53 #include <default_plan_request_adapter_parameters.hpp>
54 
56 {
57 
61 {
62 public:
63  FixStartStateCollision() : logger_(moveit::makeChildLogger("fix_start_state_collision"))
64  {
65  }
66 
67  void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
68  {
69  param_listener_ =
70  std::make_unique<default_plan_request_adapter_parameters::ParamListener>(node, parameter_namespace);
71  }
72 
73  std::string getDescription() const override
74  {
75  return "Fix Start State In Collision";
76  }
77 
78  bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
80  planning_interface::MotionPlanResponse& res) const override
81  {
82  RCLCPP_DEBUG(logger_, "Running '%s'", getDescription().c_str());
83 
84  // get the specified start state
85  moveit::core::RobotState start_state = planning_scene->getCurrentState();
86  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
87 
89  creq.group_name = req.group_name;
91  planning_scene->checkCollision(creq, cres, start_state);
92  if (cres.collision)
93  {
94  // Rerun in verbose mode
97  vcreq.verbose = true;
98  planning_scene->checkCollision(vcreq, vcres, start_state);
99 
100  if (creq.group_name.empty())
101  {
102  RCLCPP_INFO(logger_, "Start state appears to be in collision");
103  }
104  else
105  {
106  RCLCPP_INFO(logger_, "Start state appears to be in collision with respect to group %s", creq.group_name.c_str());
107  }
108 
109  auto prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
110  random_numbers::RandomNumberGenerator& rng = prefix_state->getRandomNumberGenerator();
111 
112  const std::vector<const moveit::core::JointModel*>& jmodels =
113  planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
114  planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
115  planning_scene->getRobotModel()->getJointModels();
116 
117  bool found = false;
118  const auto params = param_listener_->get_params();
119 
120  for (int c = 0; !found && c < params.max_sampling_attempts; ++c)
121  {
122  for (std::size_t i = 0; !found && i < jmodels.size(); ++i)
123  {
124  std::vector<double> sampled_variable_values(jmodels[i]->getVariableCount());
125  const double* original_values = prefix_state->getJointPositions(jmodels[i]);
126  jmodels[i]->getVariableRandomPositionsNearBy(rng, &sampled_variable_values[0], original_values,
127  jmodels[i]->getMaximumExtent() * params.jiggle_fraction);
128  start_state.setJointPositions(jmodels[i], sampled_variable_values);
130  planning_scene->checkCollision(creq, cres, start_state);
131  if (!cres.collision)
132  {
133  found = true;
134  RCLCPP_INFO(logger_, "Found a valid state near the start state at distance %lf after %d attempts",
135  prefix_state->distance(start_state), c);
136  }
137  }
138  }
139 
140  if (found)
141  {
143  moveit::core::robotStateToRobotStateMsg(start_state, req2.start_state);
144  bool solved = planner(planning_scene, req2, res);
145  if (solved && !res.trajectory->empty())
146  {
147  // heuristically decide a duration offset for the trajectory (induced by the additional point added as a
148  // prefix to the computed trajectory)
149  res.trajectory->setWayPointDurationFromPrevious(0, std::min(params.start_state_max_dt,
150  res.trajectory->getAverageSegmentDuration()));
151  res.trajectory->addPrefixWayPoint(prefix_state, 0.0);
152  // we add a prefix point, so we need to bump any previously added index positions
153  for (std::size_t& added_index : res.added_path_index)
154  {
155  added_index++;
156  }
157  res.added_path_index.push_back(0);
158  }
159  return solved;
160  }
161  else
162  {
163  RCLCPP_WARN(
164  logger_,
165  "Unable to find a valid state nearby the start state (using jiggle fraction of %lf and %lu sampling "
166  "attempts). Passing the original planning request to the planner.",
167  params.jiggle_fraction, params.max_sampling_attempts);
168  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_IN_COLLISION;
169  return false; // skip remaining adapters and/or planner
170  }
171  }
172  else
173  {
174  if (creq.group_name.empty())
175  {
176  RCLCPP_DEBUG(logger_, "Start state is valid");
177  }
178  else
179  {
180  RCLCPP_DEBUG(logger_, "Start state is valid with respect to group %s", creq.group_name.c_str());
181  }
182  return planner(planning_scene, req, res);
183  }
184  }
185 
186 private:
187  std::unique_ptr<default_plan_request_adapter_parameters::ParamListener> param_listener_;
188  rclcpp::Logger logger_;
189 };
190 } // namespace default_planner_request_adapters
191 
This fix start state collision adapter will attempt to sample a new collision-free configuration near...
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::string getDescription() const override
Get a description of this 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
Concept in MoveIt which can be used to modify the planning problem and resulting trajectory (pre-proc...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
Functional interface to call a planning function.
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.
Main namespace for MoveIt.
Definition: exceptions.h:43
rclcpp::Logger makeChildLogger(const std::string &name)
Definition: logger.cpp:93
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(stomp_moveit::StompSmoothingAdapter, planning_request_adapter::PlanningRequestAdapter)
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.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
std::vector< std::size_t > added_path_index
robot_trajectory::RobotTrajectoryPtr trajectory