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 
37 #include <ros/ros.h>
42 #include <moveit_msgs/MotionPlanRequest.h>
43 
44 namespace chomp
45 {
46 bool ChompPlanner::solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
47  const planning_interface::MotionPlanRequest& req, const ChompParameters& params,
49 {
50  ros::WallTime start_time = ros::WallTime::now();
51  if (!planning_scene)
52  {
53  ROS_ERROR_STREAM_NAMED("chomp_planner", "No planning scene initialized.");
54  res.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
55  return false;
56  }
57 
58  // get the specified start state
59  moveit::core::RobotState start_state = planning_scene->getCurrentState();
60  moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
61 
62  if (!start_state.satisfiesBounds())
63  {
64  ROS_ERROR_STREAM_NAMED("chomp_planner", "Start state violates joint limits");
65  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE;
66  return false;
67  }
68 
69  ChompTrajectory trajectory(planning_scene->getRobotModel(), 3.0, .03, req.group_name);
70  robotStateToArray(start_state, req.group_name, trajectory.getTrajectoryPoint(0));
71 
72  if (req.goal_constraints.size() != 1)
73  {
74  ROS_ERROR_NAMED("chomp_planner", "Expecting exactly one goal constraint, got: %zd", req.goal_constraints.size());
75  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
76  return false;
77  }
78 
79  if (req.goal_constraints[0].joint_constraints.empty() || !req.goal_constraints[0].position_constraints.empty() ||
80  !req.goal_constraints[0].orientation_constraints.empty())
81  {
82  ROS_ERROR_STREAM("Only joint-space goals are supported");
83  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
84  return false;
85  }
86 
87  const size_t goal_index = trajectory.getNumPoints() - 1;
88  moveit::core::RobotState goal_state(start_state);
89  for (const moveit_msgs::JointConstraint& joint_constraint : req.goal_constraints[0].joint_constraints)
90  goal_state.setVariablePosition(joint_constraint.joint_name, joint_constraint.position);
91  if (!goal_state.satisfiesBounds())
92  {
93  ROS_ERROR_STREAM_NAMED("chomp_planner", "Goal state violates joint limits");
94  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE;
95  return false;
96  }
97  robotStateToArray(goal_state, req.group_name, trajectory.getTrajectoryPoint(goal_index));
98 
99  const moveit::core::JointModelGroup* model_group =
100  planning_scene->getRobotModel()->getJointModelGroup(req.group_name);
101  // fix the goal to move the shortest angular distance for wrap-around joints:
102  for (size_t i = 0; i < model_group->getActiveJointModels().size(); i++)
103  {
104  const moveit::core::JointModel* model = model_group->getActiveJointModels()[i];
105  const moveit::core::RevoluteJointModel* revolute_joint =
106  dynamic_cast<const moveit::core::RevoluteJointModel*>(model);
107 
108  if (revolute_joint != nullptr)
109  {
110  if (revolute_joint->isContinuous())
111  {
112  double start = (trajectory)(0, i);
113  double end = (trajectory)(goal_index, i);
114  ROS_INFO_STREAM("Start is " << start << " end " << end << " short " << shortestAngularDistance(start, end));
115  (trajectory)(goal_index, i) = start + shortestAngularDistance(start, end);
116  }
117  }
118  }
119 
120  // fill in an initial trajectory based on user choice from the chomp_config.yaml file
121  if (params.trajectory_initialization_method_.compare("quintic-spline") == 0)
122  trajectory.fillInMinJerk();
123  else if (params.trajectory_initialization_method_.compare("linear") == 0)
124  trajectory.fillInLinearInterpolation();
125  else if (params.trajectory_initialization_method_.compare("cubic") == 0)
126  trajectory.fillInCubicInterpolation();
127  else if (params.trajectory_initialization_method_.compare("fillTrajectory") == 0)
128  {
129  if (res.trajectory_.empty())
130  {
131  ROS_ERROR_STREAM_NAMED("chomp_planner", "No input trajectory specified");
132  return false;
133  }
134  else if (!(trajectory.fillInFromTrajectory(*res.trajectory_[0])))
135  {
136  ROS_ERROR_STREAM_NAMED("chomp_planner", "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  ROS_ERROR_STREAM_NAMED("chomp_planner", "invalid interpolation method specified in the chomp_planner file");
144  return false;
145  }
146 
147  ROS_INFO_NAMED("chomp_planner", "CHOMP trajectory initialized using method: %s ",
148  (params.trajectory_initialization_method_).c_str());
149 
150  // optimize!
151  ros::WallTime create_time = ros::WallTime::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  ROS_ERROR_STREAM_NAMED("chomp_planner", "Could not initialize optimizer");
187  res.error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
188  return false;
189  }
190 
191  ROS_DEBUG_NAMED("chomp_planner", "Optimization took %f sec to create", (ros::WallTime::now() - create_time).toSec());
192 
193  bool optimization_result = optimizer->optimize();
194 
195  // replan with updated parameters if no solution is found
196  if (params_nonconst.enable_failure_recovery_)
197  {
198  ROS_INFO_NAMED("chomp_planner",
199  "Planned with Chomp Parameters (learning_rate, ridge_factor, "
200  "planning_time_limit, max_iterations), attempt: # %d ",
201  (replan_count + 1));
202  ROS_INFO_NAMED("chomp_planner", "Learning rate: %f ridge factor: %f planning time limit: %f max_iterations %d ",
203  params_nonconst.learning_rate_, params_nonconst.ridge_factor_,
204  params_nonconst.planning_time_limit_, params_nonconst.max_iterations_);
205 
206  if (!optimization_result && replan_count < params_nonconst.max_recovery_attempts_)
207  {
208  replan_count++;
209  replan_flag = true;
210  }
211  else
212  {
213  break;
214  }
215  }
216  else
217  break;
218  } // end of while loop
219 
220  // resetting the CHOMP Parameters to the original values after a successful plan
221  params_nonconst.setRecoveryParams(org_learning_rate, org_ridge_factor, org_planning_time_limit, org_max_iterations);
222 
223  ROS_DEBUG_NAMED("chomp_planner", "Optimization actually took %f sec to run",
224  (ros::WallTime::now() - create_time).toSec());
225  create_time = ros::WallTime::now();
226  // assume that the trajectory is now optimized, fill in the output structure:
227 
228  ROS_DEBUG_NAMED("chomp_planner", "Output trajectory has %zd joints", trajectory.getNumJoints());
229 
230  auto result = std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene->getRobotModel(), req.group_name);
231  // fill in the entire trajectory
232  for (size_t i = 0; i < trajectory.getNumPoints(); i++)
233  {
234  const Eigen::MatrixXd::RowXpr source = trajectory.getTrajectoryPoint(i);
235  auto state = std::make_shared<moveit::core::RobotState>(start_state);
236  size_t joint_index = 0;
237  for (const moveit::core::JointModel* jm : result->getGroup()->getActiveJointModels())
238  {
239  assert(jm->getVariableCount() == 1);
240  state->setVariablePosition(jm->getFirstVariableIndex(), source[joint_index++]);
241  }
242  result->addSuffixWayPoint(state, 0.0);
243  }
244 
245  res.trajectory_.resize(1);
246  res.trajectory_[0] = result;
247  res.description_.resize(1);
248  res.description_[0] = "plan";
249 
250  ROS_DEBUG_NAMED("chomp_planner", "Bottom took %f sec to create", (ros::WallTime::now() - create_time).toSec());
251  ROS_DEBUG_NAMED("chomp_planner", "Serviced planning request in %f wall-seconds",
252  (ros::WallTime::now() - start_time).toSec());
253 
254  res.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
255  res.processing_time_.resize(1);
256  res.processing_time_[0] = (ros::WallTime::now() - start_time).toSec();
257 
258  // report planning failure if path has collisions
259  if (!optimizer->isCollisionFree())
260  {
261  ROS_ERROR_STREAM_NAMED("chomp_planner", "Motion plan is invalid.");
262  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
263  return false;
264  }
265 
266  // check that final state is within goal tolerances
268  const moveit::core::RobotState& last_state = result->getLastWayPoint();
269  for (const moveit_msgs::JointConstraint& constraint : req.goal_constraints[0].joint_constraints)
270  {
271  if (!jc.configure(constraint) || !jc.decide(last_state).satisfied)
272  {
273  ROS_ERROR_STREAM_NAMED("chomp_planner", "Goal constraints are violated: " << constraint.joint_name);
274  res.error_code_.val = moveit_msgs::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED;
275  return false;
276  }
277  }
278 
279  return true;
280 }
281 } // namespace chomp
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
chomp::ChompPlanner::solve
bool solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, const ChompParameters &params, planning_interface::MotionPlanDetailedResponse &res) const
Definition: chomp_planner.cpp:78
ros.h
chomp
Definition: chomp_cost.h:43
chomp::shortestAngularDistance
static double shortestAngularDistance(double start, double end)
Definition: chomp_utils.h:109
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
moveit::core::RevoluteJointModel::isContinuous
bool isContinuous() const
chomp_trajectory.h
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
chomp_planner.h
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
planning_interface::MotionPlanDetailedResponse::trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::WallTime
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
chomp::robotStateToArray
static void robotStateToArray(const moveit::core::RobotState &state, const std::string &planning_group_name, Eigen::MatrixXd::RowXpr joint_array)
Definition: chomp_utils.h:86
start
ROSCPP_DECL void start()
moveit::core::RobotState::satisfiesBounds
bool satisfiesBounds(double margin=0.0) const
moveit::core::JointModelGroup
planning_interface::MotionPlanDetailedResponse::error_code_
moveit::core::MoveItErrorCode error_code_
conversions.h
moveit::core::RevoluteJointModel
chomp_optimizer.h
kinematic_constraints::JointConstraint
planning_scene
planning_interface::MotionPlanDetailedResponse::description_
std::vector< std::string > description_
moveit::core::JointModel
moveit::core::robotStateMsgToRobotState
bool robotStateMsgToRobotState(const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
planning_interface::MotionPlanDetailedResponse
planning_interface::MotionPlanDetailedResponse::processing_time_
std::vector< double > processing_time_


chomp_motion_planner
Author(s): Gil Jones , Mrinal Kalakrishnan
autogenerated on Sat Mar 15 2025 02:26:05