moveit2
The MoveIt Motion Planning Framework for ROS 2.
chomp_optimizer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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: Mrinal Kalakrishnan */
36 
42 #include <moveit/utils/logger.hpp>
43 
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <eigen3/Eigen/Core>
47 #include <eigen3/Eigen/LU>
48 #include <random>
49 #include <visualization_msgs/msg/marker_array.hpp>
50 
51 namespace chomp
52 {
53 namespace
54 {
55 rclcpp::Logger getLogger()
56 {
57  return moveit::getLogger("moveit.planners.chomp.optimizer");
58 }
59 } // namespace
60 
61 ChompOptimizer::ChompOptimizer(ChompTrajectory* trajectory, const planning_scene::PlanningSceneConstPtr& planning_scene,
62  const std::string& planning_group, const ChompParameters* parameters,
63  const moveit::core::RobotState& start_state)
64  : full_trajectory_(trajectory)
65  , robot_model_(planning_scene->getRobotModel())
66  , planning_group_(planning_group)
67  , parameters_(parameters)
68  , group_trajectory_(*full_trajectory_, planning_group_, DIFF_RULE_LENGTH)
69  , planning_scene_(planning_scene)
70  , state_(start_state)
71  , start_state_(start_state)
72  , initialized_(false)
73 {
74  RCLCPP_INFO(getLogger(), "Active collision detector is: %s", planning_scene->getCollisionDetectorName().c_str());
75 
76  hy_env_ = dynamic_cast<const collision_detection::CollisionEnvHybrid*>(
77  planning_scene->getCollisionEnv(planning_scene->getCollisionDetectorName()).get());
78  if (!hy_env_)
79  {
80  RCLCPP_WARN(getLogger(), "Could not initialize hybrid collision world from planning scene");
81  return;
82  }
83 
84  initialize();
85 }
86 
87 void ChompOptimizer::initialize()
88 {
89  // init some variables:
90  num_vars_free_ = group_trajectory_.getNumFreePoints();
91  num_vars_all_ = group_trajectory_.getNumPoints();
92  num_joints_ = group_trajectory_.getNumJoints();
93 
94  free_vars_start_ = group_trajectory_.getStartIndex();
95  free_vars_end_ = group_trajectory_.getEndIndex();
96 
99  req.group_name = planning_group_;
100 
101  const auto wt = std::chrono::system_clock::now();
102  hy_env_->getCollisionGradients(req, res, state_, &planning_scene_->getAllowedCollisionMatrix(), gsr_);
103  RCLCPP_INFO(getLogger(), "First coll check took %f sec",
104  std::chrono::duration<double>(std::chrono::system_clock::now() - wt).count());
105  num_collision_points_ = 0;
106  for (const collision_detection::GradientInfo& gradient : gsr_->gradients_)
107  {
108  num_collision_points_ += gradient.gradients.size();
109  }
110 
111  // set up the joint costs:
112  joint_costs_.reserve(num_joints_);
113 
114  double max_cost_scale = 0.0;
115 
116  joint_model_group_ = planning_scene_->getRobotModel()->getJointModelGroup(planning_group_);
117 
118  const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->getActiveJointModels();
119  for (size_t i = 0; i < joint_models.size(); ++i)
120  {
121  double joint_cost = 1.0;
122  // nh.param("joint_costs/" + joint_models[i]->getName(), joint_cost, 1.0);
123  std::vector<double> derivative_costs(3);
124  derivative_costs[0] = joint_cost * parameters_->smoothness_cost_velocity_;
125  derivative_costs[1] = joint_cost * parameters_->smoothness_cost_acceleration_;
126  derivative_costs[2] = joint_cost * parameters_->smoothness_cost_jerk_;
127  joint_costs_.push_back(ChompCost(group_trajectory_, i, derivative_costs, parameters_->ridge_factor_));
128  double cost_scale = joint_costs_[i].getMaxQuadCostInvValue();
129  if (max_cost_scale < cost_scale)
130  max_cost_scale = cost_scale;
131  }
132 
133  // scale the smoothness costs
134  for (int i = 0; i < num_joints_; ++i)
135  {
136  joint_costs_[i].scale(max_cost_scale);
137  }
138 
139  // allocate memory for matrices:
140  smoothness_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
141  collision_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
142  final_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
143  smoothness_derivative_ = Eigen::VectorXd::Zero(num_vars_all_);
144  jacobian_ = Eigen::MatrixXd::Zero(3, num_joints_);
145  jacobian_pseudo_inverse_ = Eigen::MatrixXd::Zero(num_joints_, 3);
146  jacobian_jacobian_tranpose_ = Eigen::MatrixXd::Zero(3, 3);
147  random_state_ = Eigen::VectorXd::Zero(num_joints_);
148  joint_state_velocities_ = Eigen::VectorXd::Zero(num_joints_);
149 
150  group_trajectory_backup_ = group_trajectory_.getTrajectory();
151  best_group_trajectory_ = group_trajectory_.getTrajectory();
152 
153  collision_point_joint_names_.resize(num_vars_all_, std::vector<std::string>(num_collision_points_));
154  collision_point_pos_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
155  collision_point_vel_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
156  collision_point_acc_eigen_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
157  joint_axes_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_joints_));
158  joint_positions_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_joints_));
159 
160  collision_point_potential_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
161  collision_point_vel_mag_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
162  collision_point_potential_gradient_.resize(num_vars_all_, EigenSTL::vector_Vector3d(num_collision_points_));
163 
164  collision_free_iteration_ = 0;
165  is_collision_free_ = false;
166  state_is_in_collision_.resize(num_vars_all_);
167  point_is_in_collision_.resize(num_vars_all_, std::vector<int>(num_collision_points_));
168 
169  last_improvement_iteration_ = -1;
170 
173 
174  // HMC initialization:
175  // momentum_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
176  // random_momentum_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
177  // random_joint_momentum_ = Eigen::VectorXd::Zero(num_vars_free_);
178  multivariate_gaussian_.clear();
179  stochasticity_factor_ = 1.0;
180  for (int i = 0; i < num_joints_; ++i)
181  {
182  multivariate_gaussian_.push_back(
183  MultivariateGaussian(Eigen::VectorXd::Zero(num_vars_free_), joint_costs_[i].getQuadraticCostInverse()));
184  }
185 
186  std::map<std::string, std::string> fixed_link_resolution_map;
187  for (int i = 0; i < num_joints_; ++i)
188  {
189  joint_names_.push_back(joint_model_group_->getActiveJointModels()[i]->getName());
190  // RCLCPP_INFO(getLogger(),"Got joint %s", joint_names_[i].c_str());
191  registerParents(joint_model_group_->getActiveJointModels()[i]);
192  fixed_link_resolution_map[joint_names_[i]] = joint_names_[i];
193  }
194 
195  for (const moveit::core::JointModel* jm : joint_model_group_->getFixedJointModels())
196  {
197  if (!jm->getParentLinkModel()) // root joint doesn't have a parent
198  continue;
199 
200  fixed_link_resolution_map[jm->getName()] = jm->getParentLinkModel()->getParentJointModel()->getName();
201  }
202 
203  // TODO - is this just the joint_roots_?
204  for (const moveit::core::LinkModel* link : joint_model_group_->getUpdatedLinkModels())
205  {
206  if (fixed_link_resolution_map.find(link->getParentJointModel()->getName()) == fixed_link_resolution_map.end())
207  {
208  const moveit::core::JointModel* parent_model = link->getParentJointModel();
209  while (true) // traverse up the tree until we find a joint we know about in joint_names_
210  {
211  if (parent_model->getParentLinkModel() == nullptr)
212  break;
213 
214  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
215  if (std::find(joint_names_.begin(), joint_names_.end(), parent_model->getName()) != joint_names_.end())
216  break;
217  }
218  fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->getName();
219  }
220  }
221 
222  int start = free_vars_start_;
223  int end = free_vars_end_;
224  for (int i = start; i <= end; ++i)
225  {
226  size_t j = 0;
227  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
228  {
229  for (size_t k = 0; k < info.sphere_locations.size(); ++k)
230  {
231  if (fixed_link_resolution_map.find(info.joint_name) != fixed_link_resolution_map.end())
232  {
233  collision_point_joint_names_[i][j] = fixed_link_resolution_map[info.joint_name];
234  }
235  else
236  {
237  RCLCPP_ERROR(getLogger(), "Couldn't find joint %s!", info.joint_name.c_str());
238  }
239  j++;
240  }
241  }
242  }
243  initialized_ = true;
244 }
245 
247 {
248  destroy();
249 }
250 
251 void ChompOptimizer::registerParents(const moveit::core::JointModel* model)
252 {
253  const moveit::core::JointModel* parent_model = nullptr;
254  bool found_root = false;
255 
256  if (model == robot_model_->getRootJoint())
257  return;
258 
259  while (!found_root)
260  {
261  if (parent_model == nullptr)
262  {
263  if (model->getParentLinkModel() == nullptr)
264  {
265  RCLCPP_ERROR(getLogger(), "Model %s not root but has nullptr link model parent", model->getName().c_str());
266  return;
267  }
268  else if (model->getParentLinkModel()->getParentJointModel() == nullptr)
269  {
270  RCLCPP_ERROR(getLogger(), "Model %s not root but has nullptr joint model parent", model->getName().c_str());
271  return;
272  }
273  parent_model = model->getParentLinkModel()->getParentJointModel();
274  }
275  else
276  {
277  if (parent_model == robot_model_->getRootJoint())
278  {
279  found_root = true;
280  }
281  else
282  {
283  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
284  }
285  }
286  joint_parent_map_[model->getName()][parent_model->getName()] = true;
287  }
288 }
289 
291 {
292  bool optimization_result = 0;
293 
294  const auto start_time = std::chrono::system_clock::now();
295  // double averageCostVelocity = 0.0;
296  // int currentCostIter = 0;
297  int cost_window = 10;
298  std::vector<double> costs(cost_window, 0.0);
299  // double minimaThreshold = 0.05;
300  bool should_break_out = false;
301 
302  // iterate
303  for (iteration_ = 0; iteration_ < parameters_->max_iterations_; ++iteration_)
304  {
305  performForwardKinematics();
306  double c_cost = getCollisionCost();
307  double s_cost = getSmoothnessCost();
308  double cost = c_cost + s_cost;
309 
310  RCLCPP_DEBUG(getLogger(), "Collision cost %f, smoothness cost: %f", c_cost, s_cost);
311 
314 
315  // if(parameters_->getAddRandomness() && currentCostIter != -1)
316  // {
317  // costs[currentCostIter] = cCost;
318  // currentCostIter++;
319 
320  // if(currentCostIter >= costWindow)
321  // {
322  // for(int i = 1; i < costWindow; ++i)
323  // {
324  // averageCostVelocity += (costs.at(i) - costs.at(i - 1));
325  // }
326 
327  // averageCostVelocity /= static_cast<double>(costWindow);
328  // currentCostIter = -1;
329  // }
330  // }
331 
332  if (iteration_ == 0)
333  {
334  best_group_trajectory_ = group_trajectory_.getTrajectory();
335  best_group_trajectory_cost_ = cost;
336  last_improvement_iteration_ = iteration_;
337  }
338  else if (cost < best_group_trajectory_cost_)
339  {
340  best_group_trajectory_ = group_trajectory_.getTrajectory();
341  best_group_trajectory_cost_ = cost;
342  last_improvement_iteration_ = iteration_;
343  }
344  calculateSmoothnessIncrements();
345  calculateCollisionIncrements();
346  calculateTotalIncrements();
347 
350 
351  // if(!parameters_->getUseHamiltonianMonteCarlo())
352  // {
353  // // non-stochastic version:
354  addIncrementsToTrajectory();
355  // }
356  // else
357  // {
358  // // hamiltonian monte carlo updates:
359  // getRandomMomentum();
360  // updateMomentum();
361  // updatePositionFromMomentum();
362  // stochasticity_factor_ *= parameters_->getHmcAnnealingFactor();
363  // }
364 
365  handleJointLimits();
366  updateFullTrajectory();
367 
368  if (iteration_ % 10 == 0)
369  {
370  RCLCPP_DEBUG(getLogger(), "iteration: %d", iteration_);
371  if (isCurrentTrajectoryMeshToMeshCollisionFree())
372  {
373  num_collision_free_iterations_ = 0;
374  RCLCPP_INFO(getLogger(), "Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
375  is_collision_free_ = true;
376  iteration_++;
377  should_break_out = true;
378  }
379  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
380 
383 
384  // ROS_DEBUG("Trajectory cost: %f (s=%f, c=%f)", getTrajectoryCost(), getSmoothnessCost(), getCollisionCost());
385  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
386  // if(safety == CollisionProximitySpace::MeshToMeshSafe)
387  // {
388  // num_collision_free_iterations_ = 0;
389  // RCLCPP_INFO(getLogger(),"Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
390  // is_collision_free_ = true;
391  // iteration_++;
392  // should_break_out = true;
393  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
394  // num_collision_free_iterations_ = parameters_->getMaxIterationsAfterCollisionFree();
395  // RCLCPP_INFO(getLogger(),"Chomp Got in collision safety at iter %d. Breaking out soon.", iteration_);
396  // is_collision_free_ = true;
397  // iteration_++;
398  // should_break_out = true;
399  // }
400  // else
401  // {
402  // is_collision_free_ = false;
403  // }
404  }
405 
406  if (!parameters_->filter_mode_)
407  {
408  if (c_cost < parameters_->collision_threshold_)
409  {
410  num_collision_free_iterations_ = parameters_->max_iterations_after_collision_free_;
411  is_collision_free_ = true;
412  iteration_++;
413  should_break_out = true;
414  }
415  else
416  {
417  RCLCPP_DEBUG(getLogger(), "cCost %f over threshold %f", c_cost, parameters_->collision_threshold_);
418  }
419  }
420 
421  if (std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() >
422  parameters_->planning_time_limit_)
423  {
424  RCLCPP_WARN(getLogger(), "Breaking out early due to time limit constraints.");
425  break;
426  }
427 
430 
431  // if(fabs(averageCostVelocity) < minimaThreshold && currentCostIter == -1 && !is_collision_free_ &&
432  // parameters_->getAddRandomness())
433  // {
434  // RCLCPP_INFO(getLogger(),"Detected local minima. Attempting to break out!");
435  // int iter = 0;
436  // bool success = false;
437  // while(iter < 20 && !success)
438  // {
439  // performForwardKinematics();
440  // double original_cost = getTrajectoryCost();
441  // group_trajectory_backup_ = group_trajectory_.getTrajectory();
442  // perturbTrajectory();
443  // handleJointLimits();
444  // updateFullTrajectory();
445  // performForwardKinematics();
446  // double new_cost = getTrajectoryCost();
447  // iter ++;
448  // if(new_cost < original_cost)
449  // {
450  // RCLCPP_INFO(getLogger(),"Got out of minimum in %d iters!", iter);
451  // averageCostVelocity = 0.0;
452  // currentCostIter = 0;
453  // success = true;
454  // }
455  // else
456  // {
457  // group_trajectory_.getTrajectory() = group_trajectory_backup_;
458  // updateFullTrajectory();
459  // currentCostIter = 0;
460  // averageCostVelocity = 0.0;
461  // success = false;
462  // }
463 
464  // }
465 
466  // if(!success)
467  // {
468  // RCLCPP_INFO(getLogger(),"Failed to exit minimum!");
469  // }
470  //}
471  // else if (currentCostIter == -1)
472  //{
473  // currentCostIter = 0;
474  // averageCostVelocity = 0.0;
475  //}
476 
477  if (should_break_out)
478  {
479  collision_free_iteration_++;
480  if (num_collision_free_iterations_ == 0)
481  {
482  break;
483  }
484  else if (collision_free_iteration_ > num_collision_free_iterations_)
485  {
486  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
487  // if(safety != CollisionProximitySpace::MeshToMeshSafe &&
488  // safety != CollisionProximitySpace::InCollisionSafe) {
489  // ROS_WARN("Apparently regressed");
490  // }
491  break;
492  }
493  }
494  }
495 
496  if (is_collision_free_)
497  {
498  optimization_result = true;
499  RCLCPP_INFO(getLogger(), "Chomp path is collision free");
500  }
501  else
502  {
503  optimization_result = false;
504  RCLCPP_ERROR(getLogger(), "Chomp path is not collision free!");
505  }
506 
507  group_trajectory_.getTrajectory() = best_group_trajectory_;
508  updateFullTrajectory();
509 
510  RCLCPP_INFO(getLogger(), "Terminated after %d iterations, using path from iteration %d", iteration_,
511  last_improvement_iteration_);
512  RCLCPP_INFO(getLogger(), "Optimization core finished in %f sec",
513  std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count());
514  RCLCPP_INFO(getLogger(), "Time per iteration %f sec",
515  std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() / (iteration_ * 1.0));
516 
517  return optimization_result;
518 }
519 
520 bool ChompOptimizer::isCurrentTrajectoryMeshToMeshCollisionFree() const
521 {
522  moveit_msgs::msg::RobotTrajectory traj;
523  traj.joint_trajectory.joint_names = joint_names_;
524 
525  for (size_t i = 0; i < group_trajectory_.getNumPoints(); ++i)
526  {
527  trajectory_msgs::msg::JointTrajectoryPoint point;
528  for (size_t j = 0; j < group_trajectory_.getNumJoints(); ++j)
529  {
530  point.positions.push_back(best_group_trajectory_(i, j));
531  }
532  traj.joint_trajectory.points.push_back(point);
533  }
534  moveit_msgs::msg::RobotState start_state_msg;
535  moveit::core::robotStateToRobotStateMsg(start_state_, start_state_msg);
536  return planning_scene_->isPathValid(start_state_msg, traj, planning_group_);
537 }
538 
539 void ChompOptimizer::calculateSmoothnessIncrements()
540 {
541  for (int i = 0; i < num_joints_; ++i)
542  {
543  joint_costs_[i].getDerivative(group_trajectory_.getJointTrajectory(i), smoothness_derivative_);
544  smoothness_increments_.col(i) = -smoothness_derivative_.segment(group_trajectory_.getStartIndex(), num_vars_free_);
545  }
546 }
547 
548 void ChompOptimizer::calculateCollisionIncrements()
549 {
550  double potential;
551  double vel_mag_sq;
552  double vel_mag;
553  Eigen::Vector3d potential_gradient;
554  Eigen::Vector3d normalized_velocity;
555  Eigen::Matrix3d orthogonal_projector;
556  Eigen::Vector3d curvature_vector;
557  Eigen::Vector3d cartesian_gradient;
558 
559  collision_increments_.setZero(num_vars_free_, num_joints_);
560 
561  int start_point = 0;
562  int end_point = free_vars_end_;
563 
564  // In stochastic descent, simply use a random point in the trajectory, rather than all the trajectory points.
565  // This is faster and guaranteed to converge, but it may take more iterations in the worst case.
566  if (parameters_->use_stochastic_descent_)
567  {
568  start_point = static_cast<int>(rsl::uniform_real(0., 1.) * (free_vars_end_ - free_vars_start_) + free_vars_start_);
569  if (start_point < free_vars_start_)
570  start_point = free_vars_start_;
571  if (start_point > free_vars_end_)
572  start_point = free_vars_end_;
573  end_point = start_point;
574  }
575  else
576  {
577  start_point = free_vars_start_;
578  }
579 
580  for (int i = start_point; i <= end_point; ++i)
581  {
582  for (int j = 0; j < num_collision_points_; ++j)
583  {
584  potential = collision_point_potential_[i][j];
585 
586  if (potential < 0.0001)
587  continue;
588 
589  potential_gradient = -collision_point_potential_gradient_[i][j];
590 
591  vel_mag = collision_point_vel_mag_[i][j];
592  vel_mag_sq = vel_mag * vel_mag;
593 
594  // all math from the CHOMP paper:
595 
596  normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag;
597  orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
598  curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq;
599  cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
600 
601  // pass it through the jacobian transpose to get the increments
602  getJacobian(i, collision_point_pos_eigen_[i][j], collision_point_joint_names_[i][j], jacobian_);
603 
604  if (parameters_->use_pseudo_inverse_)
605  {
606  calculatePseudoInverse();
607  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient;
608  }
609  else
610  {
611  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient;
612  }
613 
614  /*
615  if(point_is_in_collision_[i][j])
616  {
617  break;
618  }
619  */
620  }
621  }
622  // cout << collision_increments_ << endl;
623 }
624 
625 void ChompOptimizer::calculatePseudoInverse()
626 {
627  jacobian_jacobian_tranpose_ =
628  jacobian_ * jacobian_.transpose() + Eigen::MatrixXd::Identity(3, 3) * parameters_->pseudo_inverse_ridge_factor_;
629  jacobian_pseudo_inverse_ = jacobian_.transpose() * jacobian_jacobian_tranpose_.inverse();
630 }
631 
632 void ChompOptimizer::calculateTotalIncrements()
633 {
634  for (int i = 0; i < num_joints_; ++i)
635  {
636  final_increments_.col(i) =
637  parameters_->learning_rate_ * (joint_costs_[i].getQuadraticCostInverse() *
638  (parameters_->smoothness_cost_weight_ * smoothness_increments_.col(i) +
639  parameters_->obstacle_cost_weight_ * collision_increments_.col(i)));
640  }
641 }
642 
643 void ChompOptimizer::addIncrementsToTrajectory()
644 {
645  const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group_->getActiveJointModels();
646  for (size_t i = 0; i < joint_models.size(); ++i)
647  {
648  double scale = 1.0;
649  double max = final_increments_.col(i).maxCoeff();
650  double min = final_increments_.col(i).minCoeff();
651  double max_scale = parameters_->joint_update_limit_ / fabs(max);
652  double min_scale = parameters_->joint_update_limit_ / fabs(min);
653  if (max_scale < scale)
654  scale = max_scale;
655  if (min_scale < scale)
656  scale = min_scale;
657  group_trajectory_.getFreeTrajectoryBlock().col(i) += scale * final_increments_.col(i);
658  }
659  // ROS_DEBUG("Scale: %f",scale);
660  // group_trajectory_.getFreeTrajectoryBlock() += scale * final_increments_;
661 }
662 
663 void ChompOptimizer::updateFullTrajectory()
664 {
665  full_trajectory_->updateFromGroupTrajectory(group_trajectory_);
666 }
667 
668 void ChompOptimizer::debugCost()
669 {
670  double cost = 0.0;
671  for (int i = 0; i < num_joints_; ++i)
672  cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
673  std::cout << "Cost = " << cost << '\n';
674 }
675 
676 double ChompOptimizer::getTrajectoryCost()
677 {
678  return getSmoothnessCost() + getCollisionCost();
679 }
680 
681 double ChompOptimizer::getSmoothnessCost()
682 {
683  double smoothness_cost = 0.0;
684  // joint costs:
685  for (int i = 0; i < num_joints_; ++i)
686  smoothness_cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
687 
688  return parameters_->smoothness_cost_weight_ * smoothness_cost;
689 }
690 
691 double ChompOptimizer::getCollisionCost()
692 {
693  double collision_cost = 0.0;
694 
695  double worst_collision_cost = 0.0;
696  worst_collision_cost_state_ = -1;
697 
698  // collision costs:
699  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
700  {
701  double state_collision_cost = 0.0;
702  for (int j = 0; j < num_collision_points_; ++j)
703  {
704  state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j];
705  }
706  collision_cost += state_collision_cost;
707  if (state_collision_cost > worst_collision_cost)
708  {
709  worst_collision_cost = state_collision_cost;
710  worst_collision_cost_state_ = i;
711  }
712  }
713 
714  return parameters_->obstacle_cost_weight_ * collision_cost;
715 }
716 
717 void ChompOptimizer::computeJointProperties(int trajectory_point)
718 {
719  for (int j = 0; j < num_joints_; ++j)
720  {
721  const moveit::core::JointModel* joint_model = state_.getJointModel(joint_names_[j]);
722  const moveit::core::RevoluteJointModel* revolute_joint =
723  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
724  const moveit::core::PrismaticJointModel* prismatic_joint =
725  dynamic_cast<const moveit::core::PrismaticJointModel*>(joint_model);
726 
727  std::string parent_link_name = joint_model->getParentLinkModel()->getName();
728  std::string child_link_name = joint_model->getChildLinkModel()->getName();
729  Eigen::Isometry3d joint_transform = state_.getGlobalLinkTransform(parent_link_name) *
730  (robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
731  (state_.getJointTransform(joint_model)));
732 
733  // joint_transform = inverseWorldTransform * jointTransform;
734  Eigen::Vector3d axis;
735 
736  if (revolute_joint != nullptr)
737  {
738  axis = revolute_joint->getAxis();
739  }
740  else if (prismatic_joint != nullptr)
741  {
742  axis = prismatic_joint->getAxis();
743  }
744  else
745  {
746  axis = Eigen::Vector3d::Identity();
747  }
748 
749  axis = joint_transform * axis;
750 
751  joint_axes_[trajectory_point][j] = axis;
752  joint_positions_[trajectory_point][j] = joint_transform.translation();
753  }
754 }
755 
756 template <typename Derived>
757 void ChompOptimizer::getJacobian(int trajectory_point, Eigen::Vector3d& collision_point_pos, std::string& joint_name,
758  Eigen::MatrixBase<Derived>& jacobian) const
759 {
760  for (int j = 0; j < num_joints_; ++j)
761  {
762  if (isParent(joint_name, joint_names_[j]))
763  {
764  Eigen::Vector3d column = joint_axes_[trajectory_point][j].cross(
765  Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
766  joint_positions_[trajectory_point][j]);
767 
768  jacobian.col(j)[0] = column.x();
769  jacobian.col(j)[1] = column.y();
770  jacobian.col(j)[2] = column.z();
771  }
772  else
773  {
774  jacobian.col(j)[0] = 0.0;
775  jacobian.col(j)[1] = 0.0;
776  jacobian.col(j)[2] = 0.0;
777  }
778  }
779 }
780 
781 void ChompOptimizer::handleJointLimits()
782 {
783  const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->getActiveJointModels();
784  for (size_t joint_i = 0; joint_i < joint_models.size(); ++joint_i)
785  {
786  const moveit::core::JointModel* joint_model = joint_models[joint_i];
787 
788  if (joint_model->getType() == moveit::core::JointModel::REVOLUTE)
789  {
790  const moveit::core::RevoluteJointModel* revolute_joint =
791  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
792  if (revolute_joint->isContinuous())
793  {
794  continue;
795  }
796  }
797 
798  const moveit::core::JointModel::Bounds& bounds = joint_model->getVariableBounds();
799 
800  double joint_max = -DBL_MAX;
801  double joint_min = DBL_MAX;
802 
803  for (const moveit::core::VariableBounds& bound : bounds)
804  {
805  if (bound.min_position_ < joint_min)
806  {
807  joint_min = bound.min_position_;
808  }
809 
810  if (bound.max_position_ > joint_max)
811  {
812  joint_max = bound.max_position_;
813  }
814  }
815 
816  int count = 0;
817 
818  bool violation = false;
819  do
820  {
821  double max_abs_violation = 1e-6;
822  double max_violation = 0.0;
823  int max_violation_index = 0;
824  violation = false;
825  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
826  {
827  double amount = 0.0;
828  double absolute_amount = 0.0;
829  if (group_trajectory_(i, joint_i) > joint_max)
830  {
831  amount = joint_max - group_trajectory_(i, joint_i);
832  absolute_amount = fabs(amount);
833  }
834  else if (group_trajectory_(i, joint_i) < joint_min)
835  {
836  amount = joint_min - group_trajectory_(i, joint_i);
837  absolute_amount = fabs(amount);
838  }
839  if (absolute_amount > max_abs_violation)
840  {
841  max_abs_violation = absolute_amount;
842  max_violation = amount;
843  max_violation_index = i;
844  violation = true;
845  }
846  }
847 
848  if (violation)
849  {
850  int free_var_index = max_violation_index - free_vars_start_;
851  double multiplier =
852  max_violation / joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
853  group_trajectory_.getFreeJointTrajectoryBlock(joint_i) +=
854  multiplier * joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
855  }
856  if (++count > 10)
857  break;
858  } while (violation);
859  }
860 }
861 
862 void ChompOptimizer::performForwardKinematics()
863 {
864  double inv_time = 1.0 / group_trajectory_.getDiscretization();
865  double inv_time_sq = inv_time * inv_time;
866 
867  // calculate the forward kinematics for the fixed states only in the first iteration:
868  int start = free_vars_start_;
869  int end = free_vars_end_;
870  if (iteration_ == 0)
871  {
872  start = 0;
873  end = num_vars_all_ - 1;
874  }
875 
876  is_collision_free_ = true;
877 
878  auto total_dur = std::chrono::duration<double>::zero();
879 
880  // for each point in the trajectory
881  for (int i = start; i <= end; ++i)
882  {
883  // Set Robot state from trajectory point...
886  req.group_name = planning_group_;
887  setRobotStateFromPoint(group_trajectory_, i);
888  auto grad = std::chrono::system_clock::now();
889 
890  hy_env_->getCollisionGradients(req, res, state_, nullptr, gsr_);
891  total_dur += (std::chrono::system_clock::now() - grad);
892  computeJointProperties(i);
893  state_is_in_collision_[i] = false;
894 
895  // Keep vars in scope
896  {
897  size_t j = 0;
898  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
899  {
900  for (size_t k = 0; k < info.sphere_locations.size(); ++k)
901  {
902  collision_point_pos_eigen_[i][j][0] = info.sphere_locations[k].x();
903  collision_point_pos_eigen_[i][j][1] = info.sphere_locations[k].y();
904  collision_point_pos_eigen_[i][j][2] = info.sphere_locations[k].z();
905 
906  collision_point_potential_[i][j] =
907  getPotential(info.distances[k], info.sphere_radii[k], parameters_->min_clearance_);
908  collision_point_potential_gradient_[i][j][0] = info.gradients[k].x();
909  collision_point_potential_gradient_[i][j][1] = info.gradients[k].y();
910  collision_point_potential_gradient_[i][j][2] = info.gradients[k].z();
911 
912  point_is_in_collision_[i][j] = (info.distances[k] - info.sphere_radii[k] < info.sphere_radii[k]);
913 
914  if (point_is_in_collision_[i][j])
915  {
916  state_is_in_collision_[i] = true;
917  is_collision_free_ = false;
918  }
919  j++;
920  }
921  }
922  }
923  }
924 
925  // now, get the vel and acc for each collision point (using finite differencing)
926  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
927  {
928  for (int j = 0; j < num_collision_points_; ++j)
929  {
930  collision_point_vel_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
931  collision_point_acc_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
932  for (int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; ++k)
933  {
934  collision_point_vel_eigen_[i][j] +=
935  (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
936  collision_point_acc_eigen_[i][j] +=
937  (inv_time_sq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
938  }
939 
940  // get the norm of the velocity:
941  collision_point_vel_mag_[i][j] = collision_point_vel_eigen_[i][j].norm();
942  }
943  }
944 }
945 
946 void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory, int i)
947 {
948  const Eigen::MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i);
949 
950  std::vector<double> joint_states;
951  joint_states.reserve(group_trajectory.getNumJoints());
952  for (size_t j = 0; j < group_trajectory.getNumJoints(); ++j)
953  joint_states.emplace_back(point(0, j));
954 
955  state_.setJointGroupActivePositions(planning_group_, joint_states);
956  state_.update();
957 }
958 
959 void ChompOptimizer::perturbTrajectory()
960 {
961  // int mid_point = (free_vars_start_ + free_vars_end_) / 2;
962  if (worst_collision_cost_state_ < 0)
963  return;
964  int mid_point = worst_collision_cost_state_;
965  moveit::core::RobotState random_state = state_;
966  const moveit::core::JointModelGroup* planning_group = state_.getJointModelGroup(planning_group_);
967  random_state.setToRandomPositions(planning_group);
968  std::vector<double> vals;
969  random_state.copyJointGroupPositions(planning_group_, vals);
970  double* ptr = &vals[0];
971  Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
972  // Eigen::VectorXd random_matrix = vals;
973 
974  // convert the state into an increment
975  random_matrix -= group_trajectory_.getTrajectoryPoint(mid_point).transpose();
976 
977  // project the increment orthogonal to joint velocities
978  group_trajectory_.getJointVelocities(mid_point, joint_state_velocities_);
979  joint_state_velocities_.normalize();
980  random_matrix = (Eigen::MatrixXd::Identity(num_joints_, num_joints_) -
981  joint_state_velocities_ * joint_state_velocities_.transpose()) *
982  random_matrix;
983 
984  int mp_free_vars_index = mid_point - free_vars_start_;
985  for (int i = 0; i < num_joints_; ++i)
986  {
987  group_trajectory_.getFreeJointTrajectoryBlock(i) +=
988  joint_costs_[i].getQuadraticCostInverse().col(mp_free_vars_index) * random_state_(i);
989  }
990 }
991 
992 } // namespace chomp
ChompOptimizer(ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state)
Represents a discretized joint-space trajectory for CHOMP.
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
size_t getEndIndex() const
Gets the end index.
size_t getStartIndex() const
Gets the start index.
double getDiscretization() const
Gets the discretization time interval of the trajectory.
size_t getNumPoints() const
Gets the number of points in the trajectory.
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(size_t joint)
Gets the block of free (optimizable) trajectory for a single joint.
void getJointVelocities(size_t traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
This hybrid collision environment combines FCL and a distance field. Both can be used to calculate co...
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
const std::vector< const JointModel * > & getFixedJointModels() const
Get the fixed joints that are part of this group.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
Get the names of the links that are to be updated when the state of this group changes....
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
const std::string & getName() const
Get the name of the joint.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
JointType getType() const
Get the type of joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.hpp:72
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.hpp:108
const std::string & getName() const
The name of this link.
Definition: link_model.hpp:86
const Eigen::Vector3d & getAxis() const
Get the axis of translation.
bool isContinuous() const
Check if this joint wraps around.
const Eigen::Vector3d & getAxis() const
Get the axis of rotation.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
void update(bool force=false)
Update all transforms.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
This namespace includes the central class for representing planning contexts.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
Representation of a collision checking result.