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 
38 #include <ros/ros.h>
39 #include <visualization_msgs/MarkerArray.h>
44 #include <eigen3/Eigen/LU>
45 #include <eigen3/Eigen/Core>
46 #include <random>
47 
48 namespace chomp
49 {
50 double getRandomDouble()
51 {
52  std::default_random_engine seed;
53  std::uniform_real_distribution<> uniform(0.0, 1.0);
54  return uniform(seed);
55 }
56 
57 ChompOptimizer::ChompOptimizer(ChompTrajectory* trajectory, const planning_scene::PlanningSceneConstPtr& planning_scene,
58  const std::string& planning_group, const ChompParameters* parameters,
59  const moveit::core::RobotState& start_state)
60  : full_trajectory_(trajectory)
61  , robot_model_(planning_scene->getRobotModel())
62  , planning_group_(planning_group)
63  , parameters_(parameters)
64  , group_trajectory_(*full_trajectory_, planning_group_, DIFF_RULE_LENGTH)
65  , planning_scene_(planning_scene)
66  , state_(start_state)
67  , start_state_(start_state)
68  , initialized_(false)
69 {
70  std::vector<std::string> cd_names;
71  planning_scene->getCollisionDetectorNames(cd_names);
72 
73  ROS_INFO_STREAM("The following collision detectors are available in the planning scene.");
74  for (const std::string& cd_name : cd_names)
75  {
76  ROS_INFO_STREAM(cd_name);
77  }
78 
79  ROS_INFO_STREAM("Active collision detector is: " + planning_scene->getActiveCollisionDetectorName());
80 
81  hy_env_ = dynamic_cast<const collision_detection::CollisionEnvHybrid*>(
82  planning_scene->getCollisionEnv(planning_scene->getActiveCollisionDetectorName()).get());
83  if (!hy_env_)
84  {
85  ROS_WARN_STREAM("Could not initialize hybrid collision world from planning scene");
86  return;
87  }
88 
90 }
91 
93 {
94  // init some variables:
98 
101 
106  hy_env_->getCollisionGradients(req, res, state_, &planning_scene_->getAllowedCollisionMatrix(), gsr_);
107  ROS_INFO_STREAM("First coll check took " << (ros::WallTime::now() - wt));
109  for (const collision_detection::GradientInfo& gradient : gsr_->gradients_)
110  {
111  num_collision_points_ += gradient.gradients.size();
112  }
113 
114  // set up the joint costs:
115  joint_costs_.reserve(num_joints_);
116 
117  double max_cost_scale = 0.0;
118 
119  joint_model_group_ = planning_scene_->getRobotModel()->getJointModelGroup(planning_group_);
120 
121  const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->getActiveJointModels();
122  for (size_t i = 0; i < joint_models.size(); i++)
123  {
124  double joint_cost = 1.0;
125  // nh.param("joint_costs/" + joint_models[i]->getName(), joint_cost, 1.0);
126  std::vector<double> derivative_costs(3);
127  derivative_costs[0] = joint_cost * parameters_->smoothness_cost_velocity_;
128  derivative_costs[1] = joint_cost * parameters_->smoothness_cost_acceleration_;
129  derivative_costs[2] = joint_cost * parameters_->smoothness_cost_jerk_;
130  joint_costs_.push_back(ChompCost(group_trajectory_, i, derivative_costs, parameters_->ridge_factor_));
131  double cost_scale = joint_costs_[i].getMaxQuadCostInvValue();
132  if (max_cost_scale < cost_scale)
133  max_cost_scale = cost_scale;
134  }
135 
136  // scale the smoothness costs
137  for (int i = 0; i < num_joints_; i++)
138  {
139  joint_costs_[i].scale(max_cost_scale);
140  }
141 
142  // allocate memory for matrices:
143  smoothness_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
144  collision_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
145  final_increments_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
146  smoothness_derivative_ = Eigen::VectorXd::Zero(num_vars_all_);
147  jacobian_ = Eigen::MatrixXd::Zero(3, num_joints_);
148  jacobian_pseudo_inverse_ = Eigen::MatrixXd::Zero(num_joints_, 3);
149  jacobian_jacobian_tranpose_ = Eigen::MatrixXd::Zero(3, 3);
150  random_state_ = Eigen::VectorXd::Zero(num_joints_);
151  joint_state_velocities_ = Eigen::VectorXd::Zero(num_joints_);
152 
155 
156  collision_point_joint_names_.resize(num_vars_all_, std::vector<std::string>(num_collision_points_));
162 
163  collision_point_potential_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
164  collision_point_vel_mag_.resize(num_vars_all_, std::vector<double>(num_collision_points_));
166 
168  is_collision_free_ = false;
171 
173 
176 
177  // HMC initialization:
178  // momentum_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
179  // random_momentum_ = Eigen::MatrixXd::Zero(num_vars_free_, num_joints_);
180  // random_joint_momentum_ = Eigen::VectorXd::Zero(num_vars_free_);
181  multivariate_gaussian_.clear();
182  stochasticity_factor_ = 1.0;
183  for (int i = 0; i < num_joints_; i++)
184  {
185  multivariate_gaussian_.push_back(
186  MultivariateGaussian(Eigen::VectorXd::Zero(num_vars_free_), joint_costs_[i].getQuadraticCostInverse()));
187  }
188 
189  std::map<std::string, std::string> fixed_link_resolution_map;
190  for (int i = 0; i < num_joints_; i++)
191  {
192  joint_names_.push_back(joint_model_group_->getActiveJointModels()[i]->getName());
193  // ROS_INFO("Got joint %s", joint_names_[i].c_str());
195  fixed_link_resolution_map[joint_names_[i]] = joint_names_[i];
196  }
197 
199  {
200  if (!jm->getParentLinkModel()) // root joint doesn't have a parent
201  continue;
202 
203  fixed_link_resolution_map[jm->getName()] = jm->getParentLinkModel()->getParentJointModel()->getName();
204  }
205 
206  // TODO - is this just the joint_roots_?
208  {
209  if (fixed_link_resolution_map.find(link->getParentJointModel()->getName()) == fixed_link_resolution_map.end())
210  {
211  const moveit::core::JointModel* parent_model = link->getParentJointModel();
212  while (true) // traverse up the tree until we find a joint we know about in joint_names_
213  {
214  if (parent_model->getParentLinkModel() == nullptr)
215  break;
216 
217  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
218  if (std::find(joint_names_.begin(), joint_names_.end(), parent_model->getName()) != joint_names_.end())
219  break;
220  }
221  fixed_link_resolution_map[link->getParentJointModel()->getName()] = parent_model->getName();
222  }
223  }
224 
225  int start = free_vars_start_;
226  int end = free_vars_end_;
227  for (int i = start; i <= end; ++i)
228  {
229  size_t j = 0;
230  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
231  {
232  for (size_t k = 0; k < info.sphere_locations.size(); k++)
233  {
234  if (fixed_link_resolution_map.find(info.joint_name) != fixed_link_resolution_map.end())
235  {
236  collision_point_joint_names_[i][j] = fixed_link_resolution_map[info.joint_name];
237  }
238  else
239  {
240  ROS_ERROR("Couldn't find joint %s!", info.joint_name.c_str());
241  }
242  j++;
243  }
244  }
245  }
246  initialized_ = true;
247 }
248 
250 {
251  destroy();
252 }
253 
255 {
256  const moveit::core::JointModel* parent_model = nullptr;
257  bool found_root = false;
258 
259  if (model == robot_model_->getRootJoint())
260  return;
261 
262  while (!found_root)
263  {
264  if (parent_model == nullptr)
265  {
266  if (model->getParentLinkModel() == nullptr)
267  {
268  ROS_ERROR_STREAM("Model " << model->getName() << " not root but has NULL link model parent");
269  return;
270  }
271  else if (model->getParentLinkModel()->getParentJointModel() == nullptr)
272  {
273  ROS_ERROR_STREAM("Model " << model->getName() << " not root but has NULL joint model parent");
274  return;
275  }
276  parent_model = model->getParentLinkModel()->getParentJointModel();
277  }
278  else
279  {
280  if (parent_model == robot_model_->getRootJoint())
281  {
282  found_root = true;
283  }
284  else
285  {
286  parent_model = parent_model->getParentLinkModel()->getParentJointModel();
287  }
288  }
289  joint_parent_map_[model->getName()][parent_model->getName()] = true;
290  }
291 }
292 
294 {
295  bool optimization_result = 0;
296  ros::WallTime start_time = ros::WallTime::now();
297  // double averageCostVelocity = 0.0;
298  // int currentCostIter = 0;
299  int cost_window = 10;
300  std::vector<double> costs(cost_window, 0.0);
301  // double minimaThreshold = 0.05;
302  bool should_break_out = false;
303 
304  // iterate
306  {
307  ros::WallTime for_time = ros::WallTime::now();
309  ROS_DEBUG_STREAM("Forward kinematics took " << (ros::WallTime::now() - for_time));
310  double c_cost = getCollisionCost();
311  double s_cost = getSmoothnessCost();
312  double cost = c_cost + s_cost;
313 
314  // ROS_INFO_STREAM("Collision cost " << cCost << " smoothness cost " << sCost);
315 
318 
319  // if(parameters_->getAddRandomness() && currentCostIter != -1)
320  // {
321  // costs[currentCostIter] = cCost;
322  // currentCostIter++;
323 
324  // if(currentCostIter >= costWindow)
325  // {
326  // for(int i = 1; i < costWindow; i++)
327  // {
328  // averageCostVelocity += (costs.at(i) - costs.at(i - 1));
329  // }
330 
331  // averageCostVelocity /= (double)(costWindow);
332  // currentCostIter = -1;
333  // }
334  // }
335 
336  if (iteration_ == 0)
337  {
341  }
342  else if (cost < best_group_trajectory_cost_)
343  {
347  }
351 
354 
355  // if(!parameters_->getUseHamiltonianMonteCarlo())
356  // {
357  // // non-stochastic version:
359  // }
360  // else
361  // {
362  // // hamiltonian monte carlo updates:
363  // getRandomMomentum();
364  // updateMomentum();
365  // updatePositionFromMomentum();
366  // stochasticity_factor_ *= parameters_->getHmcAnnealingFactor();
367  // }
368 
371 
372  if (iteration_ % 10 == 0)
373  {
374  ROS_INFO("iteration: %d", iteration_);
376  {
378  ROS_INFO("Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
379  is_collision_free_ = true;
380  iteration_++;
381  should_break_out = true;
382  }
383  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
384 
387 
388  // ROS_DEBUG("Trajectory cost: %f (s=%f, c=%f)", getTrajectoryCost(), getSmoothnessCost(), getCollisionCost());
389  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
390  // if(safety == CollisionProximitySpace::MeshToMeshSafe)
391  // {
392  // num_collision_free_iterations_ = 0;
393  // ROS_INFO("Chomp Got mesh to mesh safety at iter %d. Breaking out early.", iteration_);
394  // is_collision_free_ = true;
395  // iteration_++;
396  // should_break_out = true;
397  // } else if(safety == CollisionProximitySpace::InCollisionSafe) {
398  // num_collision_free_iterations_ = parameters_->getMaxIterationsAfterCollisionFree();
399  // ROS_INFO("Chomp Got in collision safety at iter %d. Breaking out soon.", iteration_);
400  // is_collision_free_ = true;
401  // iteration_++;
402  // should_break_out = true;
403  // }
404  // else
405  // {
406  // is_collision_free_ = false;
407  // }
408  }
409 
411  {
412  if (c_cost < parameters_->collision_threshold_)
413  {
415  is_collision_free_ = true;
416  iteration_++;
417  should_break_out = true;
418  }
419  else
420  {
421  // ROS_INFO_STREAM("cCost " << cCost << " over threshold " << parameters_->getCollisionThreshold());
422  }
423  }
424 
425  if ((ros::WallTime::now() - start_time).toSec() > parameters_->planning_time_limit_)
426  {
427  ROS_WARN("Breaking out early due to time limit constraints.");
428  break;
429  }
430 
433 
434  // if(fabs(averageCostVelocity) < minimaThreshold && currentCostIter == -1 && !is_collision_free_ &&
435  // parameters_->getAddRandomness())
436  // {
437  // ROS_INFO("Detected local minima. Attempting to break out!");
438  // int iter = 0;
439  // bool success = false;
440  // while(iter < 20 && !success)
441  // {
442  // performForwardKinematics();
443  // double original_cost = getTrajectoryCost();
444  // group_trajectory_backup_ = group_trajectory_.getTrajectory();
445  // perturbTrajectory();
446  // handleJointLimits();
447  // updateFullTrajectory();
448  // performForwardKinematics();
449  // double new_cost = getTrajectoryCost();
450  // iter ++;
451  // if(new_cost < original_cost)
452  // {
453  // ROS_INFO("Got out of minimum in %d iters!", iter);
454  // averageCostVelocity = 0.0;
455  // currentCostIter = 0;
456  // success = true;
457  // }
458  // else
459  // {
460  // group_trajectory_.getTrajectory() = group_trajectory_backup_;
461  // updateFullTrajectory();
462  // currentCostIter = 0;
463  // averageCostVelocity = 0.0;
464  // success = false;
465  // }
466 
467  // }
468 
469  // if(!success)
470  // {
471  // ROS_INFO("Failed to exit minimum!");
472  // }
473  //}
474  // else if (currentCostIter == -1)
475  //{
476  // currentCostIter = 0;
477  // averageCostVelocity = 0.0;
478  //}
479 
480  if (should_break_out)
481  {
484  {
485  break;
486  }
488  {
489  // CollisionProximitySpace::TrajectorySafety safety = checkCurrentIterValidity();
490  // if(safety != CollisionProximitySpace::MeshToMeshSafe &&
491  // safety != CollisionProximitySpace::InCollisionSafe) {
492  // ROS_WARN_STREAM("Apparently regressed");
493  // }
494  break;
495  }
496  }
497  }
498 
499  if (is_collision_free_)
500  {
501  optimization_result = true;
502  ROS_INFO("Chomp path is collision free");
503  }
504  else
505  {
506  optimization_result = false;
507  ROS_ERROR("Chomp path is not collision free!");
508  }
509 
512 
513  ROS_INFO("Terminated after %d iterations, using path from iteration %d", iteration_, last_improvement_iteration_);
514  ROS_INFO("Optimization core finished in %f sec", (ros::WallTime::now() - start_time).toSec());
515  ROS_INFO_STREAM("Time per iteration " << (ros::WallTime::now() - start_time).toSec() / (iteration_ * 1.0));
516 
517  return optimization_result;
518 }
519 
521 {
522  moveit_msgs::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::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::RobotState start_state_msg;
536  return planning_scene_->isPathValid(start_state_msg, traj, planning_group_);
537 }
538 
541 
542 // CollisionProximitySpace::TrajectorySafety ChompOptimizer::checkCurrentIterValidity()
543 // {
544 // JointTrajectory jointTrajectory;
545 // jointTrajectory.joint_names = joint_names_;
546 // jointTrajectory.header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId();
547 // jointTrajectory.header.stamp = ros::Time::now();
548 // Constraints goalConstraints;
549 // Constraints pathConstraints;
550 // ArmNavigationErrorCodes errorCode;
551 // vector<ArmNavigationErrorCodes> trajectoryErrorCodes;
552 // for(int i = 0; i < group_trajectory_.getNumPoints(); i++)
553 // {
554 // JointTrajectoryPoint point;
555 // for(int j = 0; j < group_trajectory_.getNumJoints(); j++)
556 // {
557 // point.positions.push_back(best_group_trajectory_(i, j));
558 // }
559 // jointTrajectory.points.push_back(point);
560 // }
561 
562 // return collision_space_->isTrajectorySafe(jointTrajectory, goalConstraints, pathConstraints, planning_group_);
563 // /*
564 // bool valid = collision_space_->getCollisionModelsInterface()->isJointTrajectoryValid(*state_,
565 // jointTrajectory,
566 // goalConstraints,
567 // pathConstraints, errorCode,
568 // trajectoryErrorCodes, false);
569 // */
570 
571 // }
572 
574 {
575  for (int i = 0; i < num_joints_; i++)
576  {
579  }
580 }
581 
583 {
584  double potential;
585  double vel_mag_sq;
586  double vel_mag;
587  Eigen::Vector3d potential_gradient;
588  Eigen::Vector3d normalized_velocity;
589  Eigen::Matrix3d orthogonal_projector;
590  Eigen::Vector3d curvature_vector;
591  Eigen::Vector3d cartesian_gradient;
592 
594 
595  int start_point = 0;
596  int end_point = free_vars_end_;
597 
598  // In stochastic descent, simply use a random point in the trajectory, rather than all the trajectory points.
599  // This is faster and guaranteed to converge, but it may take more iterations in the worst case.
601  {
602  start_point = (int)(getRandomDouble() * (free_vars_end_ - free_vars_start_) + free_vars_start_);
603  if (start_point < free_vars_start_)
604  start_point = free_vars_start_;
605  if (start_point > free_vars_end_)
606  start_point = free_vars_end_;
607  end_point = start_point;
608  }
609  else
610  {
611  start_point = free_vars_start_;
612  }
613 
614  for (int i = start_point; i <= end_point; i++)
615  {
616  for (int j = 0; j < num_collision_points_; j++)
617  {
618  potential = collision_point_potential_[i][j];
619 
620  if (potential < 0.0001)
621  continue;
622 
623  potential_gradient = -collision_point_potential_gradient_[i][j];
624 
625  vel_mag = collision_point_vel_mag_[i][j];
626  vel_mag_sq = vel_mag * vel_mag;
627 
628  // all math from the CHOMP paper:
629 
630  normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag;
631  orthogonal_projector = Eigen::Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose());
632  curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq;
633  cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector);
634 
635  // pass it through the jacobian transpose to get the increments
637 
639  {
641  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient;
642  }
643  else
644  {
645  collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient;
646  }
647 
648  /*
649  if(point_is_in_collision_[i][j])
650  {
651  break;
652  }
653  */
654  }
655  }
656  // cout << collision_increments_ << endl;
657 }
658 
660 {
662  jacobian_ * jacobian_.transpose() + Eigen::MatrixXd::Identity(3, 3) * parameters_->pseudo_inverse_ridge_factor_;
664 }
665 
667 {
668  for (int i = 0; i < num_joints_; i++)
669  {
670  final_increments_.col(i) =
671  parameters_->learning_rate_ * (joint_costs_[i].getQuadraticCostInverse() *
674  }
675 }
676 
678 {
679  const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group_->getActiveJointModels();
680  for (size_t i = 0; i < joint_models.size(); i++)
681  {
682  double scale = 1.0;
683  double max = final_increments_.col(i).maxCoeff();
684  double min = final_increments_.col(i).minCoeff();
685  double max_scale = parameters_->joint_update_limit_ / fabs(max);
686  double min_scale = parameters_->joint_update_limit_ / fabs(min);
687  if (max_scale < scale)
688  scale = max_scale;
689  if (min_scale < scale)
690  scale = min_scale;
692  }
693  // ROS_DEBUG("Scale: %f",scale);
694  // group_trajectory_.getFreeTrajectoryBlock() += scale * final_increments_;
695 }
696 
698 {
700 }
701 
703 {
704  double cost = 0.0;
705  for (int i = 0; i < num_joints_; i++)
706  cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
707  std::cout << "Cost = " << cost << std::endl;
708 }
709 
711 {
712  return getSmoothnessCost() + getCollisionCost();
713 }
714 
716 {
717  double smoothness_cost = 0.0;
718  // joint costs:
719  for (int i = 0; i < num_joints_; i++)
720  smoothness_cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i));
721 
722  return parameters_->smoothness_cost_weight_ * smoothness_cost;
723 }
724 
726 {
727  double collision_cost = 0.0;
728 
729  double worst_collision_cost = 0.0;
731 
732  // collision costs:
733  for (int i = free_vars_start_; i <= free_vars_end_; i++)
734  {
735  double state_collision_cost = 0.0;
736  for (int j = 0; j < num_collision_points_; j++)
737  {
738  state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j];
739  }
740  collision_cost += state_collision_cost;
741  if (state_collision_cost > worst_collision_cost)
742  {
743  worst_collision_cost = state_collision_cost;
745  }
746  }
747 
748  return parameters_->obstacle_cost_weight_ * collision_cost;
749 }
750 
751 void ChompOptimizer::computeJointProperties(int trajectory_point)
752 {
753  for (int j = 0; j < num_joints_; j++)
754  {
756  const moveit::core::RevoluteJointModel* revolute_joint =
757  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
758  const moveit::core::PrismaticJointModel* prismatic_joint =
759  dynamic_cast<const moveit::core::PrismaticJointModel*>(joint_model);
760 
761  std::string parent_link_name = joint_model->getParentLinkModel()->getName();
762  std::string child_link_name = joint_model->getChildLinkModel()->getName();
763  Eigen::Isometry3d joint_transform = state_.getGlobalLinkTransform(parent_link_name) *
764  (robot_model_->getLinkModel(child_link_name)->getJointOriginTransform() *
765  (state_.getJointTransform(joint_model)));
766 
767  // joint_transform = inverseWorldTransform * jointTransform;
768  Eigen::Vector3d axis;
769 
770  if (revolute_joint != nullptr)
771  {
772  axis = revolute_joint->getAxis();
773  }
774  else if (prismatic_joint != nullptr)
775  {
776  axis = prismatic_joint->getAxis();
777  }
778  else
779  {
780  axis = Eigen::Vector3d::Identity();
781  }
782 
783  axis = joint_transform * axis;
784 
785  joint_axes_[trajectory_point][j] = axis;
786  joint_positions_[trajectory_point][j] = joint_transform.translation();
787  }
788 }
789 
790 template <typename Derived>
791 void ChompOptimizer::getJacobian(int trajectory_point, Eigen::Vector3d& collision_point_pos, std::string& joint_name,
792  Eigen::MatrixBase<Derived>& jacobian) const
793 {
794  for (int j = 0; j < num_joints_; j++)
795  {
796  if (isParent(joint_name, joint_names_[j]))
797  {
798  Eigen::Vector3d column = joint_axes_[trajectory_point][j].cross(
799  Eigen::Vector3d(collision_point_pos(0), collision_point_pos(1), collision_point_pos(2)) -
800  joint_positions_[trajectory_point][j]);
801 
802  jacobian.col(j)[0] = column.x();
803  jacobian.col(j)[1] = column.y();
804  jacobian.col(j)[2] = column.z();
805  }
806  else
807  {
808  jacobian.col(j)[0] = 0.0;
809  jacobian.col(j)[1] = 0.0;
810  jacobian.col(j)[2] = 0.0;
811  }
812  }
813 }
814 
816 {
817  const std::vector<const moveit::core::JointModel*> joint_models = joint_model_group_->getActiveJointModels();
818  for (size_t joint_i = 0; joint_i < joint_models.size(); joint_i++)
819  {
820  const moveit::core::JointModel* joint_model = joint_models[joint_i];
821 
822  if (joint_model->getType() == moveit::core::JointModel::REVOLUTE)
823  {
824  const moveit::core::RevoluteJointModel* revolute_joint =
825  dynamic_cast<const moveit::core::RevoluteJointModel*>(joint_model);
826  if (revolute_joint->isContinuous())
827  {
828  continue;
829  }
830  }
831 
832  const moveit::core::JointModel::Bounds& bounds = joint_model->getVariableBounds();
833 
834  double joint_max = -DBL_MAX;
835  double joint_min = DBL_MAX;
836 
837  for (const moveit::core::VariableBounds& bound : bounds)
838  {
839  if (bound.min_position_ < joint_min)
840  {
841  joint_min = bound.min_position_;
842  }
843 
844  if (bound.max_position_ > joint_max)
845  {
846  joint_max = bound.max_position_;
847  }
848  }
849 
850  int count = 0;
851 
852  bool violation = false;
853  do
854  {
855  double max_abs_violation = 1e-6;
856  double max_violation = 0.0;
857  int max_violation_index = 0;
858  violation = false;
859  for (int i = free_vars_start_; i <= free_vars_end_; i++)
860  {
861  double amount = 0.0;
862  double absolute_amount = 0.0;
863  if (group_trajectory_(i, joint_i) > joint_max)
864  {
865  amount = joint_max - group_trajectory_(i, joint_i);
866  absolute_amount = fabs(amount);
867  }
868  else if (group_trajectory_(i, joint_i) < joint_min)
869  {
870  amount = joint_min - group_trajectory_(i, joint_i);
871  absolute_amount = fabs(amount);
872  }
873  if (absolute_amount > max_abs_violation)
874  {
875  max_abs_violation = absolute_amount;
876  max_violation = amount;
877  max_violation_index = i;
878  violation = true;
879  }
880  }
881 
882  if (violation)
883  {
884  int free_var_index = max_violation_index - free_vars_start_;
885  double multiplier =
886  max_violation / joint_costs_[joint_i].getQuadraticCostInverse()(free_var_index, free_var_index);
888  multiplier * joint_costs_[joint_i].getQuadraticCostInverse().col(free_var_index);
889  }
890  if (++count > 10)
891  break;
892  } while (violation);
893  }
894 }
895 
897 {
898  double inv_time = 1.0 / group_trajectory_.getDiscretization();
899  double inv_time_sq = inv_time * inv_time;
900 
901  // calculate the forward kinematics for the fixed states only in the first iteration:
902  int start = free_vars_start_;
903  int end = free_vars_end_;
904  if (iteration_ == 0)
905  {
906  start = 0;
907  end = num_vars_all_ - 1;
908  }
909 
910  is_collision_free_ = true;
911 
912  ros::WallDuration total_dur(0.0);
913 
914  // for each point in the trajectory
915  for (int i = start; i <= end; ++i)
916  {
917  // Set Robot state from trajectory point...
923 
924  hy_env_->getCollisionGradients(req, res, state_, nullptr, gsr_);
925  total_dur += (ros::WallTime::now() - grad);
927  state_is_in_collision_[i] = false;
928 
929  // Keep vars in scope
930  {
931  size_t j = 0;
932  for (const collision_detection::GradientInfo& info : gsr_->gradients_)
933  {
934  for (size_t k = 0; k < info.sphere_locations.size(); k++)
935  {
936  collision_point_pos_eigen_[i][j][0] = info.sphere_locations[k].x();
937  collision_point_pos_eigen_[i][j][1] = info.sphere_locations[k].y();
938  collision_point_pos_eigen_[i][j][2] = info.sphere_locations[k].z();
939 
942  collision_point_potential_gradient_[i][j][0] = info.gradients[k].x();
943  collision_point_potential_gradient_[i][j][1] = info.gradients[k].y();
944  collision_point_potential_gradient_[i][j][2] = info.gradients[k].z();
945 
946  point_is_in_collision_[i][j] = (info.distances[k] - info.sphere_radii[k] < info.sphere_radii[k]);
947 
948  if (point_is_in_collision_[i][j])
949  {
950  state_is_in_collision_[i] = true;
951  // if(is_collision_free_ == true) {
952  // ROS_INFO_STREAM("We know it's not collision free " << g);
953  // ROS_INFO_STREAM("Sphere location " << info.sphere_locations[k].x() << " " <<
954  // info.sphere_locations[k].y() << " " << info.sphere_locations[k].z());
955  // ROS_INFO_STREAM("Gradient " << info.gradients[k].x() << " " << info.gradients[k].y() << " " <<
956  // info.gradients[k].z() << " distance " << info.distances[k] << " radii " << info.sphere_radii[k]);
957  // ROS_INFO_STREAM("Radius " << info.sphere_radii[k] << " potential " <<
958  // collision_point_potential_[i][j]);
959  // }
960 
961  is_collision_free_ = false;
962  }
963  j++;
964  }
965  }
966  }
967  }
968 
969  // ROS_INFO_STREAM("Total dur " << total_dur << " total checks " << end-start+1);
970 
971  // now, get the vel and acc for each collision point (using finite differencing)
972  for (int i = free_vars_start_; i <= free_vars_end_; i++)
973  {
974  for (int j = 0; j < num_collision_points_; j++)
975  {
976  collision_point_vel_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
977  collision_point_acc_eigen_[i][j] = Eigen::Vector3d(0, 0, 0);
978  for (int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; k++)
979  {
981  (inv_time * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
983  (inv_time_sq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i + k][j];
984  }
985 
986  // get the norm of the velocity:
988  }
989  }
990 }
991 
992 void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory, int i)
993 {
994  const Eigen::MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i);
995 
996  std::vector<double> joint_states;
997  joint_states.reserve(group_trajectory.getNumJoints());
998  for (size_t j = 0; j < group_trajectory.getNumJoints(); j++)
999  joint_states.emplace_back(point(0, j));
1000 
1002  state_.update();
1003 }
1004 
1006 {
1007  // int mid_point = (free_vars_start_ + free_vars_end_) / 2;
1009  return;
1010  int mid_point = worst_collision_cost_state_;
1011  moveit::core::RobotState random_state = state_;
1013  random_state.setToRandomPositions(planning_group);
1014  std::vector<double> vals;
1015  random_state.copyJointGroupPositions(planning_group_, vals);
1016  double* ptr = &vals[0];
1017  Eigen::Map<Eigen::VectorXd> random_matrix(ptr, vals.size());
1018  // Eigen::VectorXd random_matrix = vals;
1019 
1020  // convert the state into an increment
1021  random_matrix -= group_trajectory_.getTrajectoryPoint(mid_point).transpose();
1022 
1023  // project the increment orthogonal to joint velocities
1025  joint_state_velocities_.normalize();
1026  random_matrix = (Eigen::MatrixXd::Identity(num_joints_, num_joints_) -
1028  random_matrix;
1029 
1030  int mp_free_vars_index = mid_point - free_vars_start_;
1031  for (int i = 0; i < num_joints_; i++)
1032  {
1034  joint_costs_[i].getQuadraticCostInverse().col(mp_free_vars_index) * random_state_(i);
1035  }
1036 }
1040 // void ChompOptimizer::getRandomState(const RobotState currentState, const string& groupName, Eigen::VectorXd&
1041 // state_vec)
1042 // {
1043 // const vector<RobotState *::JointState*>& jointStates =
1044 // currentState->getJointStateGroup(groupName)->getJointStateVector();
1045 // for(size_t i = 0; i < jointStates.size(); i++)
1046 // {
1047 
1048 // bool continuous = false;
1049 
1050 // RobotState *::JointState* jointState = jointStates[i];
1051 // const RevoluteJointModel* revolute_joint
1052 // = dynamic_cast<const RevoluteJointModel*>(jointState->getJointModel());
1053 // if(revolute_joint && revolute_joint->continuous_) {
1054 // continuous = true;
1055 // }
1056 
1057 // map<string, pair<double, double> > bounds = jointState->getJointModel()->getAllVariableBounds();
1058 // int j = 0;
1059 // for(map<string, pair<double, double> >::iterator it = bounds.begin(); it != bounds.end(); it++)
1060 // {
1061 // double randVal = jointState->getJointStateValues()[j] + (getRandomDouble()
1062 // * (parameters_->getRandomJumpAmount()) -
1063 // getRandomDouble() *
1064 // (parameters_->getRandomJumpAmount()));
1065 
1066 // if(!continuous)
1067 // {
1068 // if(randVal > it->second.second)
1069 // {
1070 // randVal = it->second.second;
1071 // }
1072 // else if(randVal < it->second.first)
1073 // {
1074 // randVal = it->second.first;
1075 // }
1076 // }
1077 
1078 // ROS_DEBUG_STREAM("Joint " << it->first << " old value " << jointState->getJointStateValues()[j] << " new value
1079 // " << randVal);
1080 // state_vec(i) = randVal;
1081 
1082 // j++;
1083 // }
1084 // }
1085 // }
1086 
1087 /*
1088 void ChompOptimizer::getRandomMomentum()
1089 {
1090  if (is_collision_free_)
1091  random_momentum_.setZero(num_vars_free_, num_joints_);
1092  else
1093  for (int i = 0; i < num_joints_; ++i)
1094  {
1095  multivariate_gaussian_[i].sample(random_joint_momentum_);
1096  random_momentum_.col(i) = stochasticity_factor_ * random_joint_momentum_;
1097  }
1098 }
1099 
1100 void ChompOptimizer::updateMomentum()
1101 {
1102  // double alpha = 1.0 - parameters_->getHmcStochasticity();
1103  double eps = parameters_->getHmcDiscretization();
1104  if (iteration_ > 0)
1105  momentum_ = (momentum_ + eps * final_increments_);
1106  else
1107  momentum_ = random_momentum_;
1108  // momentum_ = alpha * (momentum_ + eps*final_increments_) + sqrt(1.0-alpha*alpha)*random_momentum_;
1109 }
1110 
1111 void ChompOptimizer::updatePositionFromMomentum()
1112 {
1113  double eps = parameters_->getHmcDiscretization();
1114  group_trajectory_.getFreeTrajectoryBlock() += eps * momentum_;
1115 }
1116 */
1117 
1118 } // namespace chomp
chomp::ChompParameters::max_iterations_after_collision_free_
int max_iterations_after_collision_free_
Definition: chomp_parameters.h:133
moveit::core::LinkModel
chomp::ChompOptimizer::initialize
void initialize()
Definition: chomp_optimizer.cpp:124
chomp::ChompParameters::planning_time_limit_
double planning_time_limit_
Definition: chomp_parameters.h:130
robot_model.h
chomp::ChompOptimizer::num_collision_free_iterations_
unsigned int num_collision_free_iterations_
Definition: chomp_optimizer.h:216
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
chomp::ChompOptimizer::random_state_
Eigen::VectorXd random_state_
Definition: chomp_optimizer.h:240
chomp::ChompOptimizer::jacobian_pseudo_inverse_
Eigen::MatrixXd jacobian_pseudo_inverse_
Definition: chomp_optimizer.h:238
chomp::ChompOptimizer::planning_group_
std::string planning_group_
Definition: chomp_optimizer.h:190
chomp::ChompOptimizer::getJacobian
void getJacobian(int trajectoryPoint, Eigen::Vector3d &collision_point_pos, std::string &jointName, Eigen::MatrixBase< Derived > &jacobian) const
Definition: chomp_optimizer.cpp:823
chomp::ChompOptimizer::parameters_
const ChompParameters * parameters_
Definition: chomp_optimizer.h:191
chomp::DIFF_RULES
static const double DIFF_RULES[3][DIFF_RULE_LENGTH]
Definition: chomp_utils.h:80
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
chomp::ChompOptimizer::addIncrementsToTrajectory
void addIncrementsToTrajectory()
Definition: chomp_optimizer.cpp:709
chomp::ChompOptimizer::multivariate_gaussian_
std::vector< MultivariateGaussian > multivariate_gaussian_
Definition: chomp_optimizer.h:222
chomp::ChompTrajectory::updateFromGroupTrajectory
void updateFromGroupTrajectory(const ChompTrajectory &group_trajectory)
Updates the full trajectory (*this) from the group trajectory.
Definition: chomp_trajectory.cpp:132
chomp::ChompOptimizer::setRobotStateFromPoint
void setRobotStateFromPoint(ChompTrajectory &group_trajectory, int i)
Definition: chomp_optimizer.cpp:1024
chomp::ChompOptimizer::collision_free_iteration_
unsigned int collision_free_iteration_
Definition: chomp_optimizer.h:186
chomp::ChompOptimizer::gsr_
collision_detection::GroupStateRepresentationPtr gsr_
Definition: chomp_optimizer.h:200
chomp::ChompOptimizer::collision_point_joint_names_
std::vector< std::vector< std::string > > collision_point_joint_names_
Definition: chomp_optimizer.h:203
chomp::ChompOptimizer::joint_model_group_
const moveit::core::JointModelGroup * joint_model_group_
Definition: chomp_optimizer.h:196
moveit::core::RobotState::getJointModel
const JointModel * getJointModel(const std::string &joint) const
chomp::ChompOptimizer::collision_point_acc_eigen_
std::vector< EigenSTL::vector_Vector3d > collision_point_acc_eigen_
Definition: chomp_optimizer.h:206
collision_detection::GradientInfo::gradients
EigenSTL::vector_Vector3d gradients
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
chomp::ChompParameters::smoothness_cost_velocity_
double smoothness_cost_velocity_
Definition: chomp_parameters.h:142
chomp::ChompTrajectory::getTrajectory
Eigen::MatrixXd & getTrajectory()
Gets the entire trajectory matrix.
Definition: chomp_trajectory.h:304
chomp::ChompOptimizer::best_group_trajectory_
Eigen::MatrixXd best_group_trajectory_
Definition: chomp_optimizer.h:213
moveit::core::VariableBounds
chomp::ChompOptimizer::destroy
void destroy()
Definition: chomp_optimizer.h:132
chomp_utils.h
chomp::ChompOptimizer::collision_point_potential_gradient_
std::vector< EigenSTL::vector_Vector3d > collision_point_potential_gradient_
Definition: chomp_optimizer.h:209
chomp::ChompTrajectory::getTrajectoryPoint
Eigen::MatrixXd::RowXpr getTrajectoryPoint(int traj_point)
Definition: chomp_trajectory.h:258
chomp::ChompOptimizer::num_collision_points_
int num_collision_points_
Definition: chomp_optimizer.h:182
chomp::ChompOptimizer::isCurrentTrajectoryMeshToMeshCollisionFree
bool isCurrentTrajectoryMeshToMeshCollisionFree() const
Definition: chomp_optimizer.cpp:552
ros.h
chomp::ChompTrajectory::getDiscretization
double getDiscretization() const
Gets the discretization time interval of the trajectory.
Definition: chomp_trajectory.h:283
chomp::ChompOptimizer::smoothness_increments_
Eigen::MatrixXd smoothness_increments_
Definition: chomp_optimizer.h:231
chomp::ChompOptimizer::getPotential
double getPotential(double field_distance, double radius, double clearance)
Definition: chomp_optimizer.h:148
chomp::ChompOptimizer::calculateSmoothnessIncrements
void calculateSmoothnessIncrements()
Definition: chomp_optimizer.cpp:605
chomp::ChompParameters::pseudo_inverse_ridge_factor_
double pseudo_inverse_ridge_factor_
enable pseudo inverse calculations or not.
Definition: chomp_parameters.h:150
collision_detection::GradientInfo::sphere_radii
std::vector< double > sphere_radii
chomp::ChompOptimizer::jacobian_jacobian_tranpose_
Eigen::MatrixXd jacobian_jacobian_tranpose_
Definition: chomp_optimizer.h:239
chomp::ChompOptimizer::joint_parent_map_
std::map< std::string, std::map< std::string, bool > > joint_parent_map_
Definition: chomp_optimizer.h:244
chomp::ChompOptimizer::collision_point_vel_eigen_
std::vector< EigenSTL::vector_Vector3d > collision_point_vel_eigen_
Definition: chomp_optimizer.h:205
moveit::core::PrismaticJointModel
moveit::core::RobotState::getJointTransform
const Eigen::Isometry3d & getJointTransform(const std::string &joint_name)
moveit::core::JointModel::getName
const std::string & getName() const
moveit::core::RobotState::setJointGroupActivePositions
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
chomp::ChompOptimizer::iteration_
int iteration_
Definition: chomp_optimizer.h:185
moveit::core::LinkModel::getParentJointModel
const JointModel * getParentJointModel() const
chomp::ChompCost
Represents the smoothness cost for CHOMP, for a single joint.
Definition: chomp_cost.h:80
chomp::ChompOptimizer::joint_axes_
std::vector< EigenSTL::vector_Vector3d > joint_axes_
Definition: chomp_optimizer.h:210
chomp::ChompOptimizer::planning_scene_
planning_scene::PlanningSceneConstPtr planning_scene_
Definition: chomp_optimizer.h:193
chomp::ChompOptimizer::joint_names_
std::vector< std::string > joint_names_
Definition: chomp_optimizer.h:243
chomp::ChompOptimizer::group_trajectory_
ChompTrajectory group_trajectory_
Definition: chomp_optimizer.h:192
chomp::ChompOptimizer::hy_env_
const collision_detection::CollisionEnvHybrid * hy_env_
Definition: chomp_optimizer.h:197
chomp::ChompTrajectory::getFreeJointTrajectoryBlock
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeJointTrajectoryBlock(size_t joint)
Gets the block of free (optimizable) trajectory for a single joint.
Definition: chomp_trajectory.h:315
chomp::ChompOptimizer::best_group_trajectory_cost_
double best_group_trajectory_cost_
Definition: chomp_optimizer.h:214
chomp::ChompOptimizer::state_is_in_collision_
std::vector< int > state_is_in_collision_
Definition: chomp_optimizer.h:225
chomp
Definition: chomp_cost.h:43
chomp::ChompOptimizer::last_improvement_iteration_
int last_improvement_iteration_
Definition: chomp_optimizer.h:215
moveit::core::RobotState
moveit::core::RobotState::copyJointGroupPositions
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
moveit::core::RobotState::getGlobalLinkTransform
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
chomp::ChompOptimizer::calculateCollisionIncrements
void calculateCollisionIncrements()
Definition: chomp_optimizer.cpp:614
moveit::core::RobotState::setToRandomPositions
void setToRandomPositions()
chomp::ChompOptimizer::ChompOptimizer
ChompOptimizer(ChompTrajectory *trajectory, const planning_scene::PlanningSceneConstPtr &planning_scene, const std::string &planning_group, const ChompParameters *parameters, const moveit::core::RobotState &start_state)
Definition: chomp_optimizer.cpp:89
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
chomp::ChompOptimizer::getCollisionCost
double getCollisionCost()
Definition: chomp_optimizer.cpp:757
chomp::ChompOptimizer::num_vars_all_
int num_vars_all_
Definition: chomp_optimizer.h:181
chomp::ChompOptimizer::free_vars_end_
int free_vars_end_
Definition: chomp_optimizer.h:184
chomp::ChompOptimizer::perturbTrajectory
void perturbTrajectory()
Definition: chomp_optimizer.cpp:1037
moveit::core::RevoluteJointModel::isContinuous
bool isContinuous() const
collision_detection::CollisionRequest
chomp::ChompTrajectory::getJointVelocities
void getJointVelocities(size_t traj_point, Eigen::MatrixBase< Derived > &velocities)
Gets the joint velocities at the given trajectory point.
Definition: chomp_trajectory.h:326
chomp::ChompOptimizer::isParent
bool isParent(const std::string &childLink, const std::string &parentLink) const
Definition: chomp_optimizer.h:246
moveit::core::JointModel::getType
JointType getType() const
chomp::ChompOptimizer::robot_model_
const moveit::core::RobotModelConstPtr & robot_model_
Definition: chomp_optimizer.h:189
moveit::core::JointModel::REVOLUTE
REVOLUTE
moveit::core::JointModel::getChildLinkModel
const LinkModel * getChildLinkModel() const
chomp::ChompOptimizer::full_trajectory_
ChompTrajectory * full_trajectory_
Definition: chomp_optimizer.h:188
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
chomp::ChompOptimizer::initialized_
bool initialized_
Definition: chomp_optimizer.h:201
chomp::ChompOptimizer::getTrajectoryCost
double getTrajectoryCost()
Definition: chomp_optimizer.cpp:742
chomp::ChompParameters::obstacle_cost_weight_
double obstacle_cost_weight_
Definition: chomp_parameters.h:137
moveit::core::JointModel::getParentLinkModel
const LinkModel * getParentLinkModel() const
moveit::core::PrismaticJointModel::getAxis
const Eigen::Vector3d & getAxis() const
chomp::ChompParameters::smoothness_cost_jerk_
double smoothness_cost_jerk_
variables associated with the cost in acceleration
Definition: chomp_parameters.h:144
collision_detection::GradientInfo::joint_name
std::string joint_name
chomp::ChompParameters::joint_update_limit_
double joint_update_limit_
set the ridge factor if pseudo inverse is enabled
Definition: chomp_parameters.h:152
chomp::ChompTrajectory::getStartIndex
size_t getStartIndex() const
Gets the start index.
Definition: chomp_trajectory.h:294
chomp::ChompOptimizer::num_vars_free_
int num_vars_free_
Definition: chomp_optimizer.h:180
chomp::ChompOptimizer::collision_increments_
Eigen::MatrixXd collision_increments_
Definition: chomp_optimizer.h:232
chomp::ChompTrajectory::getJointTrajectory
Eigen::MatrixXd::ColXpr getJointTrajectory(int joint)
Definition: chomp_trajectory.h:263
moveit::core::RobotState::update
void update(bool force=false)
chomp::ChompOptimizer::collision_point_pos_eigen_
std::vector< EigenSTL::vector_Vector3d > collision_point_pos_eigen_
Definition: chomp_optimizer.h:204
moveit::core::JointModel::getVariableBounds
const VariableBounds & getVariableBounds(const std::string &variable) const
chomp::ChompOptimizer::collision_point_potential_
std::vector< std::vector< double > > collision_point_potential_
Definition: chomp_optimizer.h:207
collision_detection::GradientInfo
chomp::ChompTrajectory::getNumJoints
size_t getNumJoints() const
Gets the number of joints in each trajectory point.
Definition: chomp_trajectory.h:278
chomp::ChompOptimizer::optimize
bool optimize()
Definition: chomp_optimizer.cpp:325
moveit::core::JointModel::Bounds
std::vector< VariableBounds > Bounds
collision_detection::CollisionResult
bound
template Interval< double > bound(const Interval< double > &i, const Interval< double > &other)
ros::WallTime::now
static WallTime now()
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
chomp::ChompOptimizer::calculateTotalIncrements
void calculateTotalIncrements()
Definition: chomp_optimizer.cpp:698
moveit::core::JointModelGroup::getFixedJointModels
const std::vector< const JointModel * > & getFixedJointModels() const
collision_detection::CollisionRequest::group_name
std::string group_name
chomp::ChompParameters::filter_mode_
bool filter_mode_
the collision threshold cost that needs to be mainted to avoid collisions
Definition: chomp_parameters.h:155
chomp::ChompOptimizer::point_is_in_collision_
std::vector< std::vector< int > > point_is_in_collision_
Definition: chomp_optimizer.h:227
chomp::ChompOptimizer::performForwardKinematics
void performForwardKinematics()
Definition: chomp_optimizer.cpp:928
ROS_ERROR
#define ROS_ERROR(...)
collision_detection::GradientInfo::sphere_locations
EigenSTL::vector_Vector3d sphere_locations
ROS_WARN
#define ROS_WARN(...)
chomp::ChompParameters::use_pseudo_inverse_
bool use_pseudo_inverse_
the noise added to the diagnal of the total quadratic cost matrix in the objective function
Definition: chomp_parameters.h:149
chomp::ChompParameters::smoothness_cost_weight_
double smoothness_cost_weight_
Definition: chomp_parameters.h:135
chomp::ChompTrajectory::getNumFreePoints
size_t getNumFreePoints() const
Gets the number of points (that are free to be optimized) in the trajectory.
Definition: chomp_trajectory.h:273
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::WallTime
chomp::ChompParameters::ridge_factor_
double ridge_factor_
Definition: chomp_parameters.h:148
chomp::ChompOptimizer::state_
moveit::core::RobotState state_
Definition: chomp_optimizer.h:194
chomp::ChompTrajectory::getEndIndex
size_t getEndIndex() const
Gets the end index.
Definition: chomp_trajectory.h:299
point
std::chrono::system_clock::time_point point
chomp::ChompParameters::max_iterations_
int max_iterations_
maximum time the optimizer can take to find a solution before terminating
Definition: chomp_parameters.h:131
chomp::DIFF_RULE_LENGTH
static const int DIFF_RULE_LENGTH
Definition: chomp_utils.h:77
chomp::ChompParameters::use_stochastic_descent_
bool use_stochastic_descent_
variables associated with the cost in jerk
Definition: chomp_parameters.h:145
chomp::ChompTrajectory::getNumPoints
size_t getNumPoints() const
Gets the number of points in the trajectory.
Definition: chomp_trajectory.h:268
start
ROSCPP_DECL void start()
chomp::ChompOptimizer::jacobian_
Eigen::MatrixXd jacobian_
Definition: chomp_optimizer.h:237
chomp::ChompOptimizer::group_trajectory_backup_
Eigen::MatrixXd group_trajectory_backup_
Definition: chomp_optimizer.h:212
chomp::ChompOptimizer::worst_collision_cost_state_
double worst_collision_cost_state_
Definition: chomp_optimizer.h:229
chomp::ChompOptimizer::is_collision_free_
bool is_collision_free_
Definition: chomp_optimizer.h:228
chomp::ChompOptimizer::updateFullTrajectory
void updateFullTrajectory()
Definition: chomp_optimizer.cpp:729
planning_scene.h
chomp::ChompOptimizer::registerParents
void registerParents(const moveit::core::JointModel *model)
Definition: chomp_optimizer.cpp:286
moveit::core::JointModelGroup::getUpdatedLinkModels
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
chomp::ChompOptimizer::joint_positions_
std::vector< EigenSTL::vector_Vector3d > joint_positions_
Definition: chomp_optimizer.h:211
collision_detection::CollisionEnvHybrid
chomp::ChompOptimizer::num_joints_
int num_joints_
Definition: chomp_optimizer.h:179
moveit::core::JointModelGroup
chomp::ChompOptimizer::start_state_
moveit::core::RobotState start_state_
Definition: chomp_optimizer.h:195
chomp::ChompOptimizer::computeJointProperties
void computeJointProperties(int trajectoryPoint)
Definition: chomp_optimizer.cpp:783
chomp::ChompParameters::min_clearance_
double min_clearance_
set the update limit for the robot joints
Definition: chomp_parameters.h:153
conversions.h
chomp::ChompParameters::learning_rate_
double learning_rate_
Definition: chomp_parameters.h:139
chomp::ChompOptimizer::smoothness_derivative_
Eigen::VectorXd smoothness_derivative_
Definition: chomp_optimizer.h:236
moveit::core::RevoluteJointModel
chomp::ChompOptimizer::final_increments_
Eigen::MatrixXd final_increments_
Definition: chomp_optimizer.h:233
ros::WallDuration
moveit::core::LinkModel::getName
const std::string & getName() const
chomp_optimizer.h
chomp::ChompOptimizer::stochasticity_factor_
double stochasticity_factor_
Definition: chomp_optimizer.h:223
moveit::core::RobotState::getJointModelGroup
const JointModelGroup * getJointModelGroup(const std::string &group) const
moveit::core::RevoluteJointModel::getAxis
const Eigen::Vector3d & getAxis() const
ROS_INFO
#define ROS_INFO(...)
planning_scene
chomp::ChompOptimizer::calculatePseudoInverse
void calculatePseudoInverse()
Definition: chomp_optimizer.cpp:691
chomp::ChompOptimizer::joint_state_velocities_
Eigen::VectorXd joint_state_velocities_
Definition: chomp_optimizer.h:241
chomp::ChompTrajectory::getFreeTrajectoryBlock
Eigen::Block< Eigen::MatrixXd, Eigen::Dynamic, Eigen::Dynamic > getFreeTrajectoryBlock()
Gets the block of the trajectory which can be optimized.
Definition: chomp_trajectory.h:309
chomp::getRandomDouble
double getRandomDouble()
Definition: chomp_optimizer.cpp:82
chomp::ChompParameters::smoothness_cost_acceleration_
double smoothness_cost_acceleration_
variables associated with the cost in velocity
Definition: chomp_parameters.h:143
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
chomp::ChompOptimizer::getSmoothnessCost
double getSmoothnessCost()
Definition: chomp_optimizer.cpp:747
chomp::ChompOptimizer::handleJointLimits
void handleJointLimits()
Definition: chomp_optimizer.cpp:847
chomp::ChompOptimizer::~ChompOptimizer
virtual ~ChompOptimizer()
Definition: chomp_optimizer.cpp:281
moveit::core::JointModel
collision_detection::CollisionEnvHybrid::getCollisionGradients
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
chomp::ChompOptimizer::debugCost
void debugCost()
Definition: chomp_optimizer.cpp:734
collision_detection::GradientInfo::distances
std::vector< double > distances
chomp::ChompOptimizer::joint_costs_
std::vector< ChompCost > joint_costs_
Definition: chomp_optimizer.h:199
chomp::ChompOptimizer::free_vars_start_
int free_vars_start_
Definition: chomp_optimizer.h:183
chomp::ChompOptimizer::collision_point_vel_mag_
std::vector< std::vector< double > > collision_point_vel_mag_
Definition: chomp_optimizer.h:208


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