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 
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <eigen3/Eigen/Core>
46 #include <eigen3/Eigen/LU>
47 #include <random>
48 #include <visualization_msgs/msg/marker_array.hpp>
49 
50 namespace chomp
51 {
52 static const rclcpp::Logger LOGGER = rclcpp::get_logger("chomp_optimizer");
53 
55 {
56  std::default_random_engine seed;
57  std::uniform_real_distribution<> uniform(0.0, 1.0);
58  return uniform(seed);
59 }
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(LOGGER, "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(LOGGER, "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(LOGGER, "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(LOGGER,"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 = nullptr;
209  bool found_root = false;
210 
211  while (!found_root)
212  {
213  if (parent_model == nullptr)
214  {
215  parent_model = link->getParentJointModel();
216  }
217  else
218  {
219  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
220  for (const std::string& joint_name : joint_names_)
221  {
222  if (parent_model->getName() == joint_name)
223  {
224  found_root = true;
225  }
226  }
227  }
228  }
229  fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->getName();
230  }
231  }
232 
233  int start = free_vars_start_;
234  int end = free_vars_end_;
235  for (int i = start; i <= end; ++i)
236  {
237  size_t j = 0;
238  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
239  {
240  for (size_t k = 0; k < info.sphere_locations.size(); ++k)
241  {
242  if (fixed_link_resolution_map.find(info.joint_name) != fixed_link_resolution_map.end())
243  {
244  collision_point_joint_names_[i][j] = fixed_link_resolution_map[info.joint_name];
245  }
246  else
247  {
248  RCLCPP_ERROR(LOGGER, "Couldn't find joint %s!", info.joint_name.c_str());
249  }
250  j++;
251  }
252  }
253  }
254  initialized_ = true;
255 }
256 
258 {
259  destroy();
260 }
261 
262 void ChompOptimizer::registerParents(const moveit::core::JointModel* model)
263 {
264  const moveit::core::JointModel* parent_model = nullptr;
265  bool found_root = false;
266 
267  if (model == robot_model_->getRootJoint())
268  return;
269 
270  while (!found_root)
271  {
272  if (parent_model == nullptr)
273  {
274  if (model->getParentLinkModel() == nullptr)
275  {
276  RCLCPP_ERROR(LOGGER, "Model %s not root but has nullptr link model parent", model->getName().c_str());
277  return;
278  }
279  else if (model->getParentLinkModel()->getParentJointModel() == nullptr)
280  {
281  RCLCPP_ERROR(LOGGER, "Model %s not root but has nullptr joint model parent", model->getName().c_str());
282  return;
283  }
284  parent_model = model->getParentLinkModel()->getParentJointModel();
285  }
286  else
287  {
288  if (parent_model == robot_model_->getRootJoint())
289  {
290  found_root = true;
291  }
292  else
293  {
294  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
295  }
296  }
297  joint_parent_map_[model->getName()][parent_model->getName()] = true;
298  }
299 }
300 
302 {
303  bool optimization_result = 0;
304 
305  const auto start_time = std::chrono::system_clock::now();
306  // double averageCostVelocity = 0.0;
307  // int currentCostIter = 0;
308  int cost_window = 10;
309  std::vector<double> costs(cost_window, 0.0);
310  // double minimaThreshold = 0.05;
311  bool should_break_out = false;
312 
313  // iterate
314  for (iteration_ = 0; iteration_ < parameters_->max_iterations_; ++iteration_)
315  {
316  performForwardKinematics();
317  double c_cost = getCollisionCost();
318  double s_cost = getSmoothnessCost();
319  double cost = c_cost + s_cost;
320 
321  RCLCPP_INFO(LOGGER, "Collision cost %f, smoothness cost: %f", c_cost, s_cost);
322 
325 
326  // if(parameters_->getAddRandomness() && currentCostIter != -1)
327  // {
328  // costs[currentCostIter] = cCost;
329  // currentCostIter++;
330 
331  // if(currentCostIter >= costWindow)
332  // {
333  // for(int i = 1; i < costWindow; ++i)
334  // {
335  // averageCostVelocity += (costs.at(i) - costs.at(i - 1));
336  // }
337 
338  // averageCostVelocity /= (double)(costWindow);
339  // currentCostIter = -1;
340  // }
341  // }
342 
343  if (iteration_ == 0)
344  {
345  best_group_trajectory_ = group_trajectory_.getTrajectory();
346  best_group_trajectory_cost_ = cost;
347  last_improvement_iteration_ = iteration_;
348  }
349  else if (cost < best_group_trajectory_cost_)
350  {
351  best_group_trajectory_ = group_trajectory_.getTrajectory();
352  best_group_trajectory_cost_ = cost;
353  last_improvement_iteration_ = iteration_;
354  }
355  calculateSmoothnessIncrements();
356  calculateCollisionIncrements();
357  calculateTotalIncrements();
358 
361 
362  // if(!parameters_->getUseHamiltonianMonteCarlo())
363  // {
364  // // non-stochastic version:
365  addIncrementsToTrajectory();
366  // }
367  // else
368  // {
369  // // hamiltonian monte carlo updates:
370  // getRandomMomentum();
371  // updateMomentum();
372  // updatePositionFromMomentum();
373  // stochasticity_factor_ *= parameters_->getHmcAnnealingFactor();
374  // }
375 
376  handleJointLimits();
377  updateFullTrajectory();
378 
379  if (iteration_ % 10 == 0)
380  {
381  RCLCPP_INFO(LOGGER, "iteration: %d", iteration_);
382  if (isCurrentTrajectoryMeshToMeshCollisionFree())
383  {
384  num_collision_free_iterations_ = 0;
385  RCLCPP_INFO(LOGGER, "Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
386  is_collision_free_ = true;
387  iteration_++;
388  should_break_out = true;
389  }
390  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
391 
394 
395  // ROS_DEBUG("Trajectory cost: %f (s=%f, c=%f)", getTrajectoryCost(), getSmoothnessCost(), getCollisionCost());
396  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
397  // if(safety == CollisionProximitySpace::MeshToMeshSafe)
398  // {
399  // num_collision_free_iterations_ = 0;
400  // RCLCPP_INFO(LOGGER,"Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
401  // is_collision_free_ = true;
402  // iteration_++;
403  // should_break_out = true;
404  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
405  // num_collision_free_iterations_ = parameters_->getMaxIterationsAfterCollisionFree();
406  // RCLCPP_INFO(LOGGER,"Chomp Got in collision safety at iter %d. Breaking out soon.", iteration_);
407  // is_collision_free_ = true;
408  // iteration_++;
409  // should_break_out = true;
410  // }
411  // else
412  // {
413  // is_collision_free_ = false;
414  // }
415  }
416 
417  if (!parameters_->filter_mode_)
418  {
419  if (c_cost < parameters_->collision_threshold_)
420  {
421  num_collision_free_iterations_ = parameters_->max_iterations_after_collision_free_;
422  is_collision_free_ = true;
423  iteration_++;
424  should_break_out = true;
425  }
426  else
427  {
428  RCLCPP_INFO(LOGGER, "cCost %f over threshold %f", c_cost, parameters_->collision_threshold_);
429  }
430  }
431 
432  if (std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() >
433  parameters_->planning_time_limit_)
434  {
435  RCLCPP_WARN(LOGGER, "Breaking out early due to time limit constraints.");
436  break;
437  }
438 
441 
442  // if(fabs(averageCostVelocity) < minimaThreshold && currentCostIter == -1 && !is_collision_free_ &&
443  // parameters_->getAddRandomness())
444  // {
445  // RCLCPP_INFO(LOGGER,"Detected local minima. Attempting to break out!");
446  // int iter = 0;
447  // bool success = false;
448  // while(iter < 20 && !success)
449  // {
450  // performForwardKinematics();
451  // double original_cost = getTrajectoryCost();
452  // group_trajectory_backup_ = group_trajectory_.getTrajectory();
453  // perturbTrajectory();
454  // handleJointLimits();
455  // updateFullTrajectory();
456  // performForwardKinematics();
457  // double new_cost = getTrajectoryCost();
458  // iter ++;
459  // if(new_cost < original_cost)
460  // {
461  // RCLCPP_INFO(LOGGER,"Got out of minimum in %d iters!", iter);
462  // averageCostVelocity = 0.0;
463  // currentCostIter = 0;
464  // success = true;
465  // }
466  // else
467  // {
468  // group_trajectory_.getTrajectory() = group_trajectory_backup_;
469  // updateFullTrajectory();
470  // currentCostIter = 0;
471  // averageCostVelocity = 0.0;
472  // success = false;
473  // }
474 
475  // }
476 
477  // if(!success)
478  // {
479  // RCLCPP_INFO(LOGGER,"Failed to exit minimum!");
480  // }
481  //}
482  // else if (currentCostIter == -1)
483  //{
484  // currentCostIter = 0;
485  // averageCostVelocity = 0.0;
486  //}
487 
488  if (should_break_out)
489  {
490  collision_free_iteration_++;
491  if (num_collision_free_iterations_ == 0)
492  {
493  break;
494  }
495  else if (collision_free_iteration_ > num_collision_free_iterations_)
496  {
497  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
498  // if(safety != CollisionProximitySpace::MeshToMeshSafe &&
499  // safety != CollisionProximitySpace::InCollisionSafe) {
500  // ROS_WARN("Apparently regressed");
501  // }
502  break;
503  }
504  }
505  }
506 
507  if (is_collision_free_)
508  {
509  optimization_result = true;
510  RCLCPP_INFO(LOGGER, "Chomp path is collision free");
511  }
512  else
513  {
514  optimization_result = false;
515  RCLCPP_ERROR(LOGGER, "Chomp path is not collision free!");
516  }
517 
518  group_trajectory_.getTrajectory() = best_group_trajectory_;
519  updateFullTrajectory();
520 
521  RCLCPP_INFO(LOGGER, "Terminated after %d iterations, using path from iteration %d", iteration_,
522  last_improvement_iteration_);
523  RCLCPP_INFO(LOGGER, "Optimization core finished in %f sec",
524  std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count());
525  RCLCPP_INFO(LOGGER, "Time per iteration %f sec",
526  std::chrono::duration<double>(std::chrono::system_clock::now() - start_time).count() / (iteration_ * 1.0));
527 
528  return optimization_result;
529 }
530 
531 bool ChompOptimizer::isCurrentTrajectoryMeshToMeshCollisionFree() const
532 {
533  moveit_msgs::msg::RobotTrajectory traj;
534  traj.joint_trajectory.joint_names = joint_names_;
535 
536  for (size_t i = 0; i < group_trajectory_.getNumPoints(); ++i)
537  {
538  trajectory_msgs::msg::JointTrajectoryPoint point;
539  for (size_t j = 0; j < group_trajectory_.getNumJoints(); ++j)
540  {
541  point.positions.push_back(best_group_trajectory_(i, j));
542  }
543  traj.joint_trajectory.points.push_back(point);
544  }
545  moveit_msgs::msg::RobotState start_state_msg;
546  moveit::core::robotStateToRobotStateMsg(start_state_, start_state_msg);
547  return planning_scene_->isPathValid(start_state_msg, traj, planning_group_);
548 }
549 
552 
553 // CollisionProximitySpace::TrajectorySafety ChompOptimizer::checkCurrentIterValidity()
554 // {
555 // JointTrajectory jointTrajectory;
556 // jointTrajectory.joint_names = joint_names_;
557 // jointTrajectory.header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId();
558 // jointTrajectory.header.stamp = ros::Time::now();
559 // Constraints goalConstraints;
560 // Constraints pathConstraints;
561 // ArmNavigationErrorCodes errorCode;
562 // vector<ArmNavigationErrorCodes> trajectoryErrorCodes;
563 // for(int i = 0; i < group_trajectory_.getNumPoints(); ++i)
564 // {
565 // JointTrajectoryPoint point;
566 // for(int j = 0; j < group_trajectory_.getNumJoints(); ++j)
567 // {
568 // point.positions.push_back(best_group_trajectory_(i, j));
569 // }
570 // jointTrajectory.points.push_back(point);
571 // }
572 
573 // return collision_space_->isTrajectorySafe(jointTrajectory, goalConstraints, pathConstraints, planning_group_);
574 // /*
575 // bool valid = collision_space_->getCollisionModelsInterface()->isJointTrajectoryValid(*state_,
576 // jointTrajectory,
577 // goalConstraints,
578 // pathConstraints, errorCode,
579 // trajectoryErrorCodes, false);
580 // */
581 
582 // }
583 
584 void ChompOptimizer::calculateSmoothnessIncrements()
585 {
586  for (int i = 0; i < num_joints_; ++i)
587  {
588  joint_costs_[i].getDerivative(group_trajectory_.getJointTrajectory(i), smoothness_derivative_);
589  smoothness_increments_.col(i) = -smoothness_derivative_.segment(group_trajectory_.getStartIndex(), num_vars_free_);
590  }
591 }
592 
593 void ChompOptimizer::calculateCollisionIncrements()
594 {
595  double potential;
596  double vel_mag_sq;
597  double vel_mag;
598  Eigen::Vector3d potential_gradient;
599  Eigen::Vector3d normalized_velocity;
600  Eigen::Matrix3d orthogonal_projector;
601  Eigen::Vector3d curvature_vector;
602  Eigen::Vector3d cartesian_gradient;
603 
604  collision_increments_.setZero(num_vars_free_, num_joints_);
605 
606  int start_point = 0;
607  int end_point = free_vars_end_;
608 
609  // In stochastic descent, simply use a random point in the trajectory, rather than all the trajectory points.
610  // This is faster and guaranteed to converge, but it may take more iterations in the worst case.
611  if (parameters_->use_stochastic_descent_)
612  {
613  start_point = static_cast<int>(getRandomDouble() * (free_vars_end_ - free_vars_start_) + free_vars_start_);
614  if (start_point < free_vars_start_)
615  start_point = free_vars_start_;
616  if (start_point > free_vars_end_)
617  start_point = free_vars_end_;
618  end_point = start_point;
619  }
620  else
621  {
622  start_point = free_vars_start_;
623  }
624 
625  for (int i = start_point; i <= end_point; ++i)
626  {
627  for (int j = 0; j < num_collision_points_; ++j)
628  {
629  potential = collision_point_potential_[i][j];
630 
631  if (potential < 0.0001)
632  continue;
633 
634  potential_gradient = -collision_point_potential_gradient_[i][j];
635 
636  vel_mag = collision_point_vel_mag_[i][j];
637  vel_mag_sq = vel_mag * vel_mag;
638 
639  // all math from the CHOMP paper:
640 
641  normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag;
642  orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
643  curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq;
644  cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
645 
646  // pass it through the jacobian transpose to get the increments
647  getJacobian(i, collision_point_pos_eigen_[i][j], collision_point_joint_names_[i][j], jacobian_);
648 
649  if (parameters_->use_pseudo_inverse_)
650  {
651  calculatePseudoInverse();
652  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient;
653  }
654  else
655  {
656  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient;
657  }
658 
659  /*
660  if(point_is_in_collision_[i][j])
661  {
662  break;
663  }
664  */
665  }
666  }
667  // cout << collision_increments_ << endl;
668 }
669 
670 void ChompOptimizer::calculatePseudoInverse()
671 {
672  jacobian_jacobian_tranpose_ =
673  jacobian_ * jacobian_.transpose() + Eigen::MatrixXd::Identity(3, 3) * parameters_->pseudo_inverse_ridge_factor_;
674  jacobian_pseudo_inverse_ = jacobian_.transpose() * jacobian_jacobian_tranpose_.inverse();
675 }
676 
677 void ChompOptimizer::calculateTotalIncrements()
678 {
679  for (int i = 0; i < num_joints_; ++i)
680  {
681  final_increments_.col(i) =
682  parameters_->learning_rate_ * (joint_costs_[i].getQuadraticCostInverse() *
683  (parameters_->smoothness_cost_weight_ * smoothness_increments_.col(i) +
684  parameters_->obstacle_cost_weight_ * collision_increments_.col(i)));
685  }
686 }
687 
688 void ChompOptimizer::addIncrementsToTrajectory()
689 {
690  const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group_->getActiveJointModels();
691  for (size_t i = 0; i < joint_models.size(); ++i)
692  {
693  double scale = 1.0;
694  double max = final_increments_.col(i).maxCoeff();
695  double min = final_increments_.col(i).minCoeff();
696  double max_scale = parameters_->joint_update_limit_ / fabs(max);
697  double min_scale = parameters_->joint_update_limit_ / fabs(min);
698  if (max_scale < scale)
699  scale = max_scale;
700  if (min_scale < scale)
701  scale = min_scale;
702  group_trajectory_.getFreeTrajectoryBlock().col(i) += scale * final_increments_.col(i);
703  }
704  // ROS_DEBUG("Scale: %f",scale);
705  // group_trajectory_.getFreeTrajectoryBlock() += scale * final_increments_;
706 }
707 
708 void ChompOptimizer::updateFullTrajectory()
709 {
710  full_trajectory_->updateFromGroupTrajectory(group_trajectory_);
711 }
712 
713 void ChompOptimizer::debugCost()
714 {
715  double cost = 0.0;
716  for (int i = 0; i < num_joints_; ++i)
717  cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
718  std::cout << "Cost = " << cost << '\n';
719 }
720 
721 double ChompOptimizer::getTrajectoryCost()
722 {
723  return getSmoothnessCost() + getCollisionCost();
724 }
725 
726 double ChompOptimizer::getSmoothnessCost()
727 {
728  double smoothness_cost = 0.0;
729  // joint costs:
730  for (int i = 0; i < num_joints_; ++i)
731  smoothness_cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
732 
733  return parameters_->smoothness_cost_weight_ * smoothness_cost;
734 }
735 
736 double ChompOptimizer::getCollisionCost()
737 {
738  double collision_cost = 0.0;
739 
740  double worst_collision_cost = 0.0;
741  worst_collision_cost_state_ = -1;
742 
743  // collision costs:
744  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
745  {
746  double state_collision_cost = 0.0;
747  for (int j = 0; j < num_collision_points_; ++j)
748  {
749  state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j];
750  }
751  collision_cost += state_collision_cost;
752  if (state_collision_cost > worst_collision_cost)
753  {
754  worst_collision_cost = state_collision_cost;
755  worst_collision_cost_state_ = i;
756  }
757  }
758 
759  return parameters_->obstacle_cost_weight_ * collision_cost;
760 }
761 
762 void ChompOptimizer::computeJointProperties(int trajectory_point)
763 {
764  for (int j = 0; j < num_joints_; ++j)
765  {
766  const moveit::core::JointModel* joint_model = state_.getJointModel(joint_names_[j]);
767  const moveit::core::RevoluteJointModel* revolute_joint =
768  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
769  const moveit::core::PrismaticJointModel* prismatic_joint =
770  dynamic_cast<const moveit::core::PrismaticJointModel*>(joint_model);
771 
772  std::string parent_link_name = joint_model->getParentLinkModel()->getName();
773  std::string child_link_name = joint_model->getChildLinkModel()->getName();
774  Eigen::Isometry3d joint_transform = state_.getGlobalLinkTransform(parent_link_name) *
775  (robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
776  (state_.getJointTransform(joint_model)));
777 
778  // joint_transform = inverseWorldTransform * jointTransform;
779  Eigen::Vector3d axis;
780 
781  if (revolute_joint != nullptr)
782  {
783  axis = revolute_joint->getAxis();
784  }
785  else if (prismatic_joint != nullptr)
786  {
787  axis = prismatic_joint->getAxis();
788  }
789  else
790  {
791  axis = Eigen::Vector3d::Identity();
792  }
793 
794  axis = joint_transform * axis;
795 
796  joint_axes_[trajectory_point][j] = axis;
797  joint_positions_[trajectory_point][j] = joint_transform.translation();
798  }
799 }
800 
801 template <typename Derived>
802 void ChompOptimizer::getJacobian(int trajectory_point, Eigen::Vector3d& collision_point_pos, std::string& joint_name,
803  Eigen::MatrixBase<Derived>& jacobian) const
804 {
805  for (int j = 0; j < num_joints_; ++j)
806  {
807  if (isParent(joint_name, joint_names_[j]))
808  {
809  Eigen::Vector3d column = joint_axes_[trajectory_point][j].cross(
810  Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
811  joint_positions_[trajectory_point][j]);
812 
813  jacobian.col(j)[0] = column.x();
814  jacobian.col(j)[1] = column.y();
815  jacobian.col(j)[2] = column.z();
816  }
817  else
818  {
819  jacobian.col(j)[0] = 0.0;
820  jacobian.col(j)[1] = 0.0;
821  jacobian.col(j)[2] = 0.0;
822  }
823  }
824 }
825 
826 void ChompOptimizer::handleJointLimits()
827 {
828  const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->getActiveJointModels();
829  for (size_t joint_i = 0; joint_i < joint_models.size(); ++joint_i)
830  {
831  const moveit::core::JointModel* joint_model = joint_models[joint_i];
832 
833  if (joint_model->getType() == moveit::core::JointModel::REVOLUTE)
834  {
835  const moveit::core::RevoluteJointModel* revolute_joint =
836  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
837  if (revolute_joint->isContinuous())
838  {
839  continue;
840  }
841  }
842 
843  const moveit::core::JointModel::Bounds& bounds = joint_model->getVariableBounds();
844 
845  double joint_max = -DBL_MAX;
846  double joint_min = DBL_MAX;
847 
848  for (const moveit::core::VariableBounds& bound : bounds)
849  {
850  if (bound.min_position_ < joint_min)
851  {
852  joint_min = bound.min_position_;
853  }
854 
855  if (bound.max_position_ > joint_max)
856  {
857  joint_max = bound.max_position_;
858  }
859  }
860 
861  int count = 0;
862 
863  bool violation = false;
864  do
865  {
866  double max_abs_violation = 1e-6;
867  double max_violation = 0.0;
868  int max_violation_index = 0;
869  violation = false;
870  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
871  {
872  double amount = 0.0;
873  double absolute_amount = 0.0;
874  if (group_trajectory_(i, joint_i) > joint_max)
875  {
876  amount = joint_max - group_trajectory_(i, joint_i);
877  absolute_amount = fabs(amount);
878  }
879  else if (group_trajectory_(i, joint_i) < joint_min)
880  {
881  amount = joint_min - group_trajectory_(i, joint_i);
882  absolute_amount = fabs(amount);
883  }
884  if (absolute_amount > max_abs_violation)
885  {
886  max_abs_violation = absolute_amount;
887  max_violation = amount;
888  max_violation_index = i;
889  violation = true;
890  }
891  }
892 
893  if (violation)
894  {
895  int free_var_index = max_violation_index - free_vars_start_;
896  double multiplier =
897  max_violation / joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
898  group_trajectory_.getFreeJointTrajectoryBlock(joint_i) +=
899  multiplier * joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
900  }
901  if (++count > 10)
902  break;
903  } while (violation);
904  }
905 }
906 
907 void ChompOptimizer::performForwardKinematics()
908 {
909  double inv_time = 1.0 / group_trajectory_.getDiscretization();
910  double inv_time_sq = inv_time * inv_time;
911 
912  // calculate the forward kinematics for the fixed states only in the first iteration:
913  int start = free_vars_start_;
914  int end = free_vars_end_;
915  if (iteration_ == 0)
916  {
917  start = 0;
918  end = num_vars_all_ - 1;
919  }
920 
921  is_collision_free_ = true;
922 
923  auto total_dur = std::chrono::duration<double>::zero();
924 
925  // for each point in the trajectory
926  for (int i = start; i <= end; ++i)
927  {
928  // Set Robot state from trajectory point...
931  req.group_name = planning_group_;
932  setRobotStateFromPoint(group_trajectory_, i);
933  auto grad = std::chrono::system_clock::now();
934 
935  hy_env_->getCollisionGradients(req, res, state_, nullptr, gsr_);
936  total_dur += (std::chrono::system_clock::now() - grad);
937  computeJointProperties(i);
938  state_is_in_collision_[i] = false;
939 
940  // Keep vars in scope
941  {
942  size_t j = 0;
943  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
944  {
945  for (size_t k = 0; k < info.sphere_locations.size(); ++k)
946  {
947  collision_point_pos_eigen_[i][j][0] = info.sphere_locations[k].x();
948  collision_point_pos_eigen_[i][j][1] = info.sphere_locations[k].y();
949  collision_point_pos_eigen_[i][j][2] = info.sphere_locations[k].z();
950 
951  collision_point_potential_[i][j] =
952  getPotential(info.distances[k], info.sphere_radii[k], parameters_->min_clearance_);
953  collision_point_potential_gradient_[i][j][0] = info.gradients[k].x();
954  collision_point_potential_gradient_[i][j][1] = info.gradients[k].y();
955  collision_point_potential_gradient_[i][j][2] = info.gradients[k].z();
956 
957  point_is_in_collision_[i][j] = (info.distances[k] - info.sphere_radii[k] < info.sphere_radii[k]);
958 
959  if (point_is_in_collision_[i][j])
960  {
961  state_is_in_collision_[i] = true;
962  // if(is_collision_free_ == true) {
963  // RCLCPP_INFO(LOGGER,"We know it's not collision free " << g);
964  // RCLCPP_INFO(LOGGER,"Sphere location " << info.sphere_locations[k].x() << " " <<
965  // info.sphere_locations[k].y() << " " << info.sphere_locations[k].z());
966  // RCLCPP_INFO(LOGGER,"Gradient " << info.gradients[k].x() << " " << info.gradients[k].y() << " " <<
967  // info.gradients[k].z() << " distance " << info.distances[k] << " radii " << info.sphere_radii[k]);
968  // RCLCPP_INFO(LOGGER,"Radius " << info.sphere_radii[k] << " potential " <<
969  // collision_point_potential_[i][j]);
970  // }
971 
972  is_collision_free_ = false;
973  }
974  j++;
975  }
976  }
977  }
978  }
979 
980  // RCLCPP_INFO(LOGGER,"Total dur " << total_dur << " total checks " << end-start+1);
981 
982  // now, get the vel and acc for each collision point (using finite differencing)
983  for (int i = free_vars_start_; i <= free_vars_end_; ++i)
984  {
985  for (int j = 0; j < num_collision_points_; ++j)
986  {
987  collision_point_vel_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
988  collision_point_acc_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
989  for (int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; ++k)
990  {
991  collision_point_vel_eigen_[i][j] +=
992  (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
993  collision_point_acc_eigen_[i][j] +=
994  (inv_time_sq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
995  }
996 
997  // get the norm of the velocity:
998  collision_point_vel_mag_[i][j] = collision_point_vel_eigen_[i][j].norm();
999  }
1000  }
1001 }
1002 
1003 void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory, int i)
1004 {
1005  const Eigen::MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i);
1006 
1007  std::vector<double> joint_states;
1008  joint_states.reserve(group_trajectory.getNumJoints());
1009  for (size_t j = 0; j < group_trajectory.getNumJoints(); ++j)
1010  joint_states.emplace_back(point(0, j));
1011 
1012  state_.setJointGroupPositions(planning_group_, joint_states);
1013  state_.update();
1014 }
1015 
1016 void ChompOptimizer::perturbTrajectory()
1017 {
1018  // int mid_point = (free_vars_start_ + free_vars_end_) / 2;
1019  if (worst_collision_cost_state_ < 0)
1020  return;
1021  int mid_point = worst_collision_cost_state_;
1022  moveit::core::RobotState random_state = state_;
1023  const moveit::core::JointModelGroup* planning_group = state_.getJointModelGroup(planning_group_);
1024  random_state.setToRandomPositions(planning_group);
1025  std::vector<double> vals;
1026  random_state.copyJointGroupPositions(planning_group_, vals);
1027  double* ptr = &vals[0];
1028  Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
1029  // Eigen::VectorXd random_matrix = vals;
1030 
1031  // convert the state into an increment
1032  random_matrix -= group_trajectory_.getTrajectoryPoint(mid_point).transpose();
1033 
1034  // project the increment orthogonal to joint velocities
1035  group_trajectory_.getJointVelocities(mid_point, joint_state_velocities_);
1036  joint_state_velocities_.normalize();
1037  random_matrix = (Eigen::MatrixXd::Identity(num_joints_, num_joints_) -
1038  joint_state_velocities_ * joint_state_velocities_.transpose()) *
1039  random_matrix;
1040 
1041  int mp_free_vars_index = mid_point - free_vars_start_;
1042  for (int i = 0; i < num_joints_; ++i)
1043  {
1044  group_trajectory_.getFreeJointTrajectoryBlock(i) +=
1045  joint_costs_[i].getQuadraticCostInverse().col(mp_free_vars_index) * random_state_(i);
1046  }
1047 }
1048 
1051 // void ChompOptimizer::getRandomState(const RobotState currentState, const string& groupName, Eigen::VectorXd&
1052 // state_vec)
1053 // {
1054 // const vector<RobotState *::JointState*>& jointStates =
1055 // currentState->getJointStateGroup(groupName)->getJointStateVector();
1056 // for(size_t i = 0; i < jointStates.size(); ++i)
1057 // {
1058 
1059 // bool continuous = false;
1060 
1061 // RobotState *::JointState* jointState = jointStates[i];
1062 // const RevoluteJointModel* revolute_joint
1063 // = dynamic_cast<const RevoluteJointModel*>(jointState->getJointModel());
1064 // if(revolute_joint && revolute_joint->continuous_) {
1065 // continuous = true;
1066 // }
1067 
1068 // map<string, pair<double, double> > bounds = jointState->getJointModel()->getAllVariableBounds();
1069 // int j = 0;
1070 // for(map<string, pair<double, double> >::iterator it = bounds.begin(); it != bounds.end(); ++it)
1071 // {
1072 // double randVal = jointState->getJointStateValues()[j] + (getRandomDouble()
1073 // * (parameters_->getRandomJumpAmount()) -
1074 // getRandomDouble() *
1075 // (parameters_->getRandomJumpAmount()));
1076 
1077 // if(!continuous)
1078 // {
1079 // if(randVal > it->second.second)
1080 // {
1081 // randVal = it->second.second;
1082 // }
1083 // else if(randVal < it->second.first)
1084 // {
1085 // randVal = it->second.first;
1086 // }
1087 // }
1088 
1089 // ROS_DEBUG("Joint " << it->first << " old value " << jointState->getJointStateValues()[j] << " new value
1090 // " << randVal);
1091 // state_vec(i) = randVal;
1092 
1093 // j++;
1094 // }
1095 // }
1096 // }
1097 
1098 /*
1099 void ChompOptimizer::getRandomMomentum()
1100 {
1101  if (is_collision_free_)
1102  random_momentum_.setZero(num_vars_free_, num_joints_);
1103  else
1104  for (int i = 0; i < num_joints_; ++i)
1105  {
1106  multivariate_gaussian_[i].sample(random_joint_momentum_);
1107  random_momentum_.col(i) = stochasticity_factor_ * random_joint_momentum_;
1108  }
1109 }
1110 
1111 void ChompOptimizer::updateMomentum()
1112 {
1113  // double alpha = 1.0 - parameters_->getHmcStochasticity();
1114  double eps = parameters_->getHmcDiscretization();
1115  if (iteration_ > 0)
1116  momentum_ = (momentum_ + eps * final_increments_);
1117  else
1118  momentum_ = random_momentum_;
1119  // momentum_ = alpha * (momentum_ + eps*final_increments_) + sqrt(1.0-alpha*alpha)*random_momentum_;
1120 }
1121 
1122 void ChompOptimizer::updatePositionFromMomentum()
1123 {
1124  double eps = parameters_->getHmcDiscretization();
1125  group_trajectory_.getFreeTrajectoryBlock() += eps * momentum_;
1126 }
1127 */
1128 
1129 } // 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....
Definition: joint_model.h:117
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
Definition: joint_model.h:162
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
Definition: joint_model.h:168
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
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.
Definition: joint_model.h:151
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:72
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.h:108
const std::string & getName() const
The name of this link.
Definition: link_model.h: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.h: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...
Definition: robot_state.h:1339
const JointModel * getJointModel(const std::string &joint) const
Get the model of a particular joint.
Definition: robot_state.h:128
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
Definition: robot_state.h:1401
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
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...
Definition: robot_state.h:691
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:134
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void update(bool force=false)
Update all transforms.
double getRandomDouble()
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h: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.
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.