moveit2
The MoveIt Motion Planning Framework for ROS 2.
chomp_planner.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: E. Gil Jones */
36 
41 #include <tf2/LinearMath/Quaternion.h>
42 #include <tf2_eigen/tf2_eigen.hpp>
43 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
44 
45 #include <chrono>
46 
47 namespace chomp
48 {
49 static const rclcpp::Logger LOGGER = rclcpp::get_logger("chomp_planner");
50 
51 bool ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
54 {
55  auto start_time = std::chrono::system_clock::now();
56  if (!planning_scene)
57  {
58  RCLCPP_ERROR(LOGGER, "No planning scene initialized.");
59  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
60  return false;
61  }
62 
63  // get the specified start state
64  moveit::core::RobotState start_state = planning_scene->getCurrentState();
65  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
66 
67  if (!start_state.satisfiesBounds())
68  {
69  RCLCPP_ERROR(LOGGER, "Start state violates joint limits");
70  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
71  return false;
72  }
73 
74  ChompTrajectory trajectory(planning_scene->getRobotModel(), 3.0, .03, req.group_name);
75  robotStateToArray(start_state, req.group_name, trajectory.getTrajectoryPoint(0));
76 
77  if (req.goal_constraints.size() != 1)
78  {
79  RCLCPP_ERROR(LOGGER, "Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
80  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
81  return false;
82  }
83 
84  if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
85  !req.goal_constraints[0].orientation_constraints.empty())
86  {
87  RCLCPP_ERROR(LOGGER, "Only joint-space goals are supported");
88  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
89  return false;
90  }
91 
92  const size_t goal_index = trajectory.getNumPoints() - 1;
93  moveit::core::RobotState goal_state(start_state);
94  for (const moveit_msgs::msg::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
95  goal_state.setVariablePosition(joint_constraint.joint_name, joint_constraint.position);
96  if (!goal_state.satisfiesBounds())
97  {
98  RCLCPP_ERROR(LOGGER, "Goal state violates joint limits");
99  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE;
100  return false;
101  }
102  robotStateToArray(goal_state, req.group_name, trajectory.getTrajectoryPoint(goal_index));
103 
104  const moveit::core::JointModelGroup* model_group =
105  planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
106  // fix the goal to move the shortest angular distance for wrap-around joints:
107  for (size_t i = 0; i < model_group->getActiveJointModels().size(); ++i)
108  {
109  const moveit::core::JointModel* model = model_group->getActiveJointModels()[i];
110  const moveit::core::RevoluteJointModel* revolute_joint =
111  dynamic_cast<const moveit::core::RevoluteJointModel*>(model);
112 
113  if (revolute_joint != nullptr)
114  {
115  if (revolute_joint->isContinuous())
116  {
117  double start = (trajectory)(0, i);
118  double end = (trajectory)(goal_index, i);
119  RCLCPP_INFO(LOGGER, "Start is %f end %f short %f", start, end, shortestAngularDistance(start, end));
120  (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
121  }
122  }
123  }
124 
125  // fill in an initial trajectory based on user choice from the chomp_config.yaml file
126  if (params.trajectory_initialization_method_.compare("quintic-spline") == 0)
127  trajectory.fillInMinJerk();
128  else if (params.trajectory_initialization_method_.compare("linear") == 0)
129  trajectory.fillInLinearInterpolation();
130  else if (params.trajectory_initialization_method_.compare("cubic") == 0)
131  trajectory.fillInCubicInterpolation();
132  else if (params.trajectory_initialization_method_.compare("fillTrajectory") == 0)
133  {
134  if (!(trajectory.fillInFromTrajectory(*res.trajectory_[0])))
135  {
136  RCLCPP_ERROR(LOGGER, "Input trajectory has less than 2 points, "
137  "trajectory must contain at least start and goal state");
138  return false;
139  }
140  }
141  else
142  {
143  RCLCPP_ERROR(LOGGER, "invalid interpolation method specified in the chomp_planner file");
144  return false;
145  }
146 
147  RCLCPP_INFO(LOGGER, "CHOMP trajectory initialized using method: %s ",
148  (params.trajectory_initialization_method_).c_str());
149 
150  // optimize!
151  auto create_time = std::chrono::system_clock::now();
152 
153  int replan_count = 0;
154  bool replan_flag = false;
155  double org_learning_rate = 0.04, org_ridge_factor = 0.0, org_planning_time_limit = 10;
156  int org_max_iterations = 200;
157 
158  // storing the initial chomp parameters values
159  org_learning_rate = params.learning_rate_;
160  org_ridge_factor = params.ridge_factor_;
161  org_planning_time_limit = params.planning_time_limit_;
162  org_max_iterations = params.max_iterations_;
163 
164  std::unique_ptr<ChompOptimizer> optimizer;
165 
166  // create a non_const_params variable which stores the non constant version of the const params variable
167  ChompParameters params_nonconst = params;
168 
169  // while loop for replanning (recovery behaviour) if collision free optimized solution not found
170  while (true)
171  {
172  if (replan_flag)
173  {
174  // increase learning rate in hope to find a successful path; increase ridge factor to avoid obstacles; add 5
175  // additional secs in hope to find a solution; increase maximum iterations
176  params_nonconst.setRecoveryParams(params_nonconst.learning_rate_ + 0.02, params_nonconst.ridge_factor_ + 0.002,
177  params_nonconst.planning_time_limit_ + 5, params_nonconst.max_iterations_ + 50);
178  }
179 
180  // initialize a ChompOptimizer object to load up the optimizer with default parameters or with updated parameters in
181  // case of a recovery behaviour
182  optimizer =
183  std::make_unique<ChompOptimizer>(&trajectory, planning_scene, req.group_name, &params_nonconst, start_state);
184  if (!optimizer->isInitialized())
185  {
186  RCLCPP_ERROR(LOGGER, "Could not initialize optimizer");
187  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
188  return false;
189  }
190 
191  RCLCPP_DEBUG(LOGGER, "Optimization took %ld sec to create",
192  (std::chrono::system_clock::now() - create_time).count());
193 
194  bool optimization_result = optimizer->optimize();
195 
196  // replan with updated parameters if no solution is found
197  if (params_nonconst.enable_failure_recovery_)
198  {
199  RCLCPP_INFO(LOGGER,
200  "Planned with Chomp Parameters (learning_rate, ridge_factor, "
201  "planning_time_limit, max_iterations), attempt: # %d ",
202  (replan_count + 1));
203  RCLCPP_INFO(LOGGER, "Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
204  params_nonconst.learning_rate_, params_nonconst.ridge_factor_, params_nonconst.planning_time_limit_,
205  params_nonconst.max_iterations_);
206 
207  if (!optimization_result && replan_count < params_nonconst.max_recovery_attempts_)
208  {
209  replan_count++;
210  replan_flag = true;
211  }
212  else
213  {
214  break;
215  }
216  }
217  else
218  break;
219  } // end of while loop
220 
221  // resetting the CHOMP Parameters to the original values after a successful plan
222  params_nonconst.setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
223 
224  RCLCPP_DEBUG(LOGGER, "Optimization actually took %ld sec to run",
225  (std::chrono::system_clock::now() - create_time).count());
226  create_time = std::chrono::system_clock::now();
227  // assume that the trajectory is now optimized, fill in the output structure:
228 
229  RCLCPP_DEBUG(LOGGER, "Output trajectory has %zd joints", trajectory.getNumJoints());
230 
231  auto result = std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene->getRobotModel(), req.group_name);
232  // fill in the entire trajectory
233  for (size_t i = 0; i < trajectory.getNumPoints(); ++i)
234  {
235  const Eigen::MatrixXd::RowXpr source = trajectory.getTrajectoryPoint(i);
236  auto state = std::make_shared<moveit::core::RobotState>(start_state);
237  size_t joint_index = 0;
238  for (const moveit::core::JointModel* jm : result->getGroup()->getActiveJointModels())
239  {
240  assert(jm->getVariableCount() == 1);
241  state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
242  }
243  result->addSuffixWayPoint(state, 0.0);
244  }
245 
246  res.trajectory_.resize(1);
247  res.trajectory_[0] = result;
248 
249  RCLCPP_DEBUG(LOGGER, "Bottom took %ld sec to create", (std::chrono::system_clock::now() - create_time).count());
250  RCLCPP_DEBUG(LOGGER, "Serviced planning request in %ld wall-seconds",
251  (std::chrono::system_clock::now() - start_time).count());
252 
253  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
254  res.processing_time_.resize(1);
255  res.processing_time_[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
256 
257  // report planning failure if path has collisions
258  if (not optimizer->isCollisionFree())
259  {
260  RCLCPP_ERROR(LOGGER, "Motion plan is invalid.");
261  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
262  return false;
263  }
264 
265  // check that final state is within goal tolerances
267  const moveit::core::RobotState& last_state = result->getLastWayPoint();
268  for (const moveit_msgs::msg::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
269  {
270  if (!jc.configure(constraint) || !jc.decide(last_state).satisfied)
271  {
272  RCLCPP_ERROR(LOGGER, "Goal constraints are violated: %s", constraint.joint_name.c_str());
273  res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
274  return false;
275  }
276  }
277 
278  res.processing_time_.resize(1);
279  res.processing_time_[0] = std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count();
280 
281  return true;
282 }
283 
284 } // namespace chomp
std::string trajectory_initialization_method_
void setRecoveryParams(double learning_rate, double ridge_factor, int planning_time_limit, int max_iterations)
bool solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, const ChompParameters &params, planning_interface::MotionPlanDetailedResponse &res) const
Represents a discretized joint-space trajectory for CHOMP.
size_t getNumPoints() const
Gets the number of points in the trajectory.
void fillInCubicInterpolation()
Generates a cubic interpolation of the trajectory from the start index to end index.
bool fillInFromTrajectory(const robot_trajectory::RobotTrajectory &trajectory)
Receives the path obtained from a given MotionPlanDetailedResponse res object's trajectory (e....
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
void fillInLinearInterpolation()
Generates a linearly interpolated trajectory from the start index to end index.
void fillInMinJerk()
Generates a minimum jerk trajectory from the start index to end index.
Class for handling single DOF joint constraints.
ConstraintEvaluationResult decide(const moveit::core::RobotState &state, bool verbose=false) const override
Decide whether the constraint is satisfied in the indicated state.
bool configure(const moveit_msgs::msg::JointConstraint &jc)
Configure the constraint based on a moveit_msgs::msg::JointConstraint.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
Definition: robot_state.h:188
bool satisfiesBounds(double margin=0.0) const
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.
bool satisfied
Whether or not the constraint or constraints were satisfied.
moveit_msgs::msg::MoveItErrorCodes error_code_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_