$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00037 #include <chomp_motion_planner/chomp_optimizer.h> 00038 #include <ros/ros.h> 00039 #include <visualization_msgs/MarkerArray.h> 00040 #include <chomp_motion_planner/chomp_utils.h> 00041 #include <planning_models/kinematic_model.h> 00042 #include <eigen3/Eigen/LU> 00043 #include <eigen3/Eigen/Core> 00044 using namespace std; 00045 using namespace Eigen; 00046 using namespace planning_models; 00047 using namespace collision_proximity; 00048 using namespace arm_navigation_msgs; 00049 using namespace trajectory_msgs; 00050 00051 namespace chomp 00052 { 00053 double getRandomDouble() 00054 { 00055 return ((double)random() / (double)RAND_MAX); 00056 } 00057 00058 ChompOptimizer::ChompOptimizer(ChompTrajectory *trajectory, KinematicModel *robot_model, 00059 const string& planning_group,const ChompParameters *parameters, const ros::Publisher& vis_marker_array_publisher, 00060 const ros::Publisher& vis_marker_publisher, CollisionProximitySpace *collision_space) : 00061 full_trajectory_(trajectory), robot_model_(robot_model), planning_group_(planning_group), parameters_(parameters), 00062 collision_space_(collision_space), group_trajectory_(*full_trajectory_, planning_group_, DIFF_RULE_LENGTH), 00063 vis_marker_array_pub_(vis_marker_array_publisher), vis_marker_pub_(vis_marker_publisher) 00064 { 00065 initialize(); 00066 } 00067 00068 void ChompOptimizer::initialize() 00069 { 00070 robot_state_ = collision_space_->getCollisionModelsInterface()->getPlanningSceneState(); 00071 // init some variables: 00072 num_vars_free_ = group_trajectory_.getNumFreePoints(); 00073 num_vars_all_ = group_trajectory_.getNumPoints(); 00074 num_joints_ = group_trajectory_.getNumJoints(); 00075 00076 free_vars_start_ = group_trajectory_.getStartIndex(); 00077 free_vars_end_ = group_trajectory_.getEndIndex(); 00078 00079 vector<GradientInfo> infos; 00080 collision_space_->getStateGradients(infos); 00081 00082 num_collision_points_ = 0; 00083 for(size_t i = 0; i < infos.size(); i++) 00084 { 00085 GradientInfo& info = infos[i]; 00086 num_collision_points_ += info.sphere_locations.size(); 00087 00088 } 00089 00090 // set up the joint costs: 00091 joint_costs_.reserve(num_joints_); 00092 00093 double max_cost_scale = 0.0; 00094 ros::NodeHandle nh("~"); 00095 00096 map<string, KinematicModel::JointModelGroup*> jointMap = robot_model_->getJointModelGroupMap(); 00097 KinematicModel::JointModelGroup* jointModelGroup = jointMap[planning_group_]; 00098 vector<const KinematicModel::JointModel*> jointModels = jointModelGroup->getJointModels(); 00099 for(size_t i = 0; i < jointModels.size(); i++) 00100 { 00101 const KinematicModel::JointModel* model = jointModels[i]; 00102 double joint_cost = 1.0; 00103 string joint_name = model->getName(); 00104 nh.param("joint_costs/" + joint_name, joint_cost, 1.0); 00105 vector<double> derivative_costs(3); 00106 derivative_costs[0] = joint_cost * parameters_->getSmoothnessCostVelocity(); 00107 derivative_costs[1] = joint_cost * parameters_->getSmoothnessCostAcceleration(); 00108 derivative_costs[2] = joint_cost * parameters_->getSmoothnessCostJerk(); 00109 00110 joint_costs_.push_back(ChompCost(group_trajectory_, i, derivative_costs, parameters_->getRidgeFactor())); 00111 double cost_scale = joint_costs_[i].getMaxQuadCostInvValue(); 00112 if(max_cost_scale < cost_scale) 00113 max_cost_scale = cost_scale; 00114 } 00115 00116 // scale the smoothness costs 00117 for(int i = 0; i < num_joints_; i++) 00118 { 00119 joint_costs_[i].scale(max_cost_scale); 00120 } 00121 00122 // allocate memory for matrices: 00123 smoothness_increments_ = MatrixXd::Zero(num_vars_free_, num_joints_); 00124 collision_increments_ = MatrixXd::Zero(num_vars_free_, num_joints_); 00125 final_increments_ = MatrixXd::Zero(num_vars_free_, num_joints_); 00126 smoothness_derivative_ = VectorXd::Zero(num_vars_all_); 00127 jacobian_ = MatrixXd::Zero(3, num_joints_); 00128 jacobian_pseudo_inverse_ = MatrixXd::Zero(num_joints_, 3); 00129 jacobian_jacobian_tranpose_ = MatrixXd::Zero(3, 3); 00130 random_state_ = VectorXd::Zero(num_joints_); 00131 joint_state_velocities_ = VectorXd::Zero(num_joints_); 00132 00133 group_trajectory_backup_ = group_trajectory_.getTrajectory(); 00134 best_group_trajectory_ = group_trajectory_.getTrajectory(); 00135 00136 collision_point_joint_names_.resize(num_vars_all_, vector<string>(num_collision_points_)); 00137 collision_point_pos_eigen_.resize(num_vars_all_, vector<Vector3d>(num_collision_points_)); 00138 collision_point_vel_eigen_.resize(num_vars_all_, vector<Vector3d>(num_collision_points_)); 00139 collision_point_acc_eigen_.resize(num_vars_all_, vector<Vector3d>(num_collision_points_)); 00140 joint_axes_.resize(num_vars_all_, vector<btVector3>(num_joints_)); 00141 joint_positions_.resize(num_vars_all_, vector<btVector3>(num_joints_)); 00142 00143 collision_point_potential_.resize(num_vars_all_, vector<double>(num_collision_points_)); 00144 collision_point_vel_mag_.resize(num_vars_all_, vector<double>(num_collision_points_)); 00145 collision_point_potential_gradient_.resize(num_vars_all_, vector<Vector3d>(num_collision_points_)); 00146 00147 collision_free_iteration_ = 0; 00148 is_collision_free_ = false; 00149 state_is_in_collision_.resize(num_vars_all_); 00150 point_is_in_collision_.resize(num_vars_all_, vector<int>(num_collision_points_)); 00151 00152 last_improvement_iteration_ = -1; 00153 00154 // HMC initialization: 00155 momentum_ = MatrixXd::Zero(num_vars_free_, num_joints_); 00156 random_momentum_ = MatrixXd::Zero(num_vars_free_, num_joints_); 00157 random_joint_momentum_ = VectorXd::Zero(num_vars_free_); 00158 multivariate_gaussian_.clear(); 00159 stochasticity_factor_ = 1.0; 00160 for(int i = 0; i < num_joints_; i++) 00161 { 00162 multivariate_gaussian_.push_back( 00163 MultivariateGaussian(VectorXd::Zero(num_vars_free_), 00164 joint_costs_[i].getQuadraticCostInverse())); 00165 } 00166 00167 map<string, KinematicModel::JointModelGroup*> groupMap = robot_model_->getJointModelGroupMap(); 00168 KinematicModel::JointModelGroup* modelGroup = groupMap[planning_group_]; 00169 map<string, string> fixedLinkResolutionMap; 00170 for(int i = 0; i < num_joints_; i++) 00171 { 00172 joint_names_.push_back(modelGroup->getJointModels()[i]->getName()); 00173 ROS_INFO("Got joint %s", joint_names_[i].c_str()); 00174 registerParents(modelGroup->getJointModels()[i]); 00175 fixedLinkResolutionMap[joint_names_[i]] = joint_names_[i]; 00176 } 00177 00178 for(size_t i = 0; i < modelGroup->getFixedJointModels().size(); i ++) 00179 { 00180 const KinematicModel::JointModel* model = modelGroup->getFixedJointModels()[i]; 00181 fixedLinkResolutionMap[model->getName()] = model->getParentLinkModel()->getParentJointModel()->getName(); 00182 } 00183 00184 for(size_t i = 0; i < modelGroup->getUpdatedLinkModels().size(); i ++) 00185 { 00186 if(fixedLinkResolutionMap.find(modelGroup->getUpdatedLinkModels()[i]->getParentJointModel()->getName()) == fixedLinkResolutionMap.end()) 00187 { 00188 const KinematicModel::JointModel* parentModel = NULL; 00189 bool foundRoot = false; 00190 00191 while(!foundRoot) 00192 { 00193 if(parentModel == NULL) 00194 { 00195 parentModel = modelGroup->getUpdatedLinkModels()[i]->getParentJointModel(); 00196 } 00197 else 00198 { 00199 parentModel = parentModel->getParentLinkModel()->getParentJointModel(); 00200 for(size_t j = 0; j < joint_names_.size(); j++) 00201 { 00202 if(parentModel->getName() == joint_names_[j]) 00203 { 00204 foundRoot = true; 00205 } 00206 } 00207 } 00208 } 00209 fixedLinkResolutionMap[modelGroup->getUpdatedLinkModels()[i]->getParentJointModel()->getName()] = parentModel->getName(); 00210 } 00211 } 00212 00213 for(map<string, map<string, bool> >::iterator it = joint_parent_map_.begin(); it != joint_parent_map_.end(); it++) 00214 { 00215 stringstream ss; 00216 ss << it->first << " Parents : {"; 00217 00218 for(map<string, bool>::iterator it2 = it->second.begin(); it2 != it->second.end(); it2++) 00219 { 00220 ss << it2->first << ","; 00221 } 00222 ss << "}"; 00223 ROS_INFO("%s",ss.str().c_str()); 00224 } 00225 00226 int start = free_vars_start_; 00227 int end = free_vars_end_; 00228 vector<GradientInfo> gradients; 00229 collision_space_->getStateGradients(gradients); 00230 for(int i = start; i <= end; ++i) 00231 { 00232 size_t j = 0; 00233 for(size_t g = 0; g < gradients.size(); g++) 00234 { 00235 GradientInfo& info = gradients[g]; 00236 00237 for(size_t k = 0; k < info.sphere_locations.size(); k++) 00238 { 00239 if(fixedLinkResolutionMap.find(info.joint_name) != fixedLinkResolutionMap.end()) 00240 { 00241 collision_point_joint_names_[i][j] = fixedLinkResolutionMap[info.joint_name]; 00242 } 00243 else 00244 { 00245 ROS_ERROR("Couldn't find joint %s!", info.joint_name.c_str()); 00246 } 00247 j++; 00248 } 00249 } 00250 } 00251 } 00252 00253 ChompOptimizer::~ChompOptimizer() 00254 { 00255 destroy(); 00256 } 00257 00258 void ChompOptimizer::registerParents(const KinematicModel::JointModel* model) 00259 { 00260 const KinematicModel::JointModel* parentModel = NULL; 00261 bool foundRoot = false; 00262 00263 while(!foundRoot) 00264 { 00265 if(parentModel == NULL) 00266 { 00267 parentModel = model->getParentLinkModel()->getParentJointModel(); 00268 } 00269 else 00270 { 00271 parentModel = parentModel->getParentLinkModel()->getParentJointModel(); 00272 00273 if(parentModel == robot_model_->getRoot()) 00274 { 00275 foundRoot = true; 00276 } 00277 } 00278 joint_parent_map_[model->getName()][parentModel->getName()] = true; 00279 } 00280 } 00281 00282 void ChompOptimizer::optimize() 00283 { 00284 ros::WallTime start_time = ros::WallTime::now(); 00285 double averageCostVelocity = 0.0; 00286 int currentCostIter = 0; 00287 int costWindow = 10; 00288 vector<double>costs(costWindow, 0.0); 00289 double minimaThreshold = 0.01; 00290 bool shouldBreakOut = false; 00291 00292 if(parameters_->getAnimatePath()) 00293 { 00294 animatePath(); 00295 } 00296 00297 // iterate 00298 for(iteration_ = 0; iteration_ < parameters_->getMaxIterations(); iteration_++) 00299 { 00300 performForwardKinematics(); 00301 double cCost = getCollisionCost(); 00302 double sCost = getSmoothnessCost(); 00303 double cost = cCost + sCost; 00304 00305 if(parameters_->getAddRandomness() && currentCostIter != -1) 00306 { 00307 costs[currentCostIter] = cCost; 00308 currentCostIter++; 00309 00310 if(currentCostIter >= costWindow) 00311 { 00312 for(int i = 1; i < costWindow; i++) 00313 { 00314 averageCostVelocity += (costs.at(i) - costs.at(i - 1)); 00315 } 00316 00317 averageCostVelocity /= (double)(costWindow); 00318 currentCostIter = -1; 00319 } 00320 } 00321 if(iteration_ == 0) 00322 { 00323 best_group_trajectory_ = group_trajectory_.getTrajectory(); 00324 best_group_trajectory_cost_ = cost; 00325 } 00326 else 00327 { 00328 if(cost < best_group_trajectory_cost_) 00329 { 00330 best_group_trajectory_ = group_trajectory_.getTrajectory(); 00331 best_group_trajectory_cost_ = cost; 00332 last_improvement_iteration_ = iteration_; 00333 } 00334 } 00335 calculateSmoothnessIncrements(); 00336 calculateCollisionIncrements(); 00337 calculateTotalIncrements(); 00338 00339 if(!parameters_->getUseHamiltonianMonteCarlo()) 00340 { 00341 // non-stochastic version: 00342 addIncrementsToTrajectory(); 00343 } 00344 else 00345 { 00346 // hamiltonian monte carlo updates: 00347 getRandomMomentum(); 00348 updateMomentum(); 00349 updatePositionFromMomentum(); 00350 stochasticity_factor_ *= parameters_->getHmcAnnealingFactor(); 00351 } 00352 handleJointLimits(); 00353 updateFullTrajectory(); 00354 00355 if(iteration_ % 10 == 0) 00356 { 00357 ROS_DEBUG("Trajectory cost: %f (s=%f, c=%f)", getTrajectoryCost(), getSmoothnessCost(), getCollisionCost()); 00358 if(checkCurrentIterValidity()) 00359 { 00360 ROS_INFO("Chomp Got safe iteration at iter %d. Breaking out early.", iteration_); 00361 is_collision_free_ = true; 00362 iteration_++; 00363 shouldBreakOut = true; 00364 } 00365 else 00366 { 00367 is_collision_free_ = false; 00368 } 00369 } 00370 00371 if(!parameters_->getFilterMode()) 00372 { 00373 if(cCost < parameters_->getCollisionThreshold()) 00374 { 00375 if(checkCurrentIterValidity()) 00376 { 00377 is_collision_free_ = true; 00378 iteration_++; 00379 shouldBreakOut = true; 00380 } 00381 else 00382 { 00383 is_collision_free_ = false; 00384 ROS_DEBUG("CHOMP thought trajectory was collision free, but it is not safe!"); 00385 } 00386 } 00387 } 00388 00389 00390 if((ros::WallTime::now() - start_time).toSec() > parameters_->getPlanningTimeLimit() && !parameters_->getAnimatePath() && !parameters_->getAnimateEndeffector()) 00391 { 00392 ROS_WARN("Breaking out early due to time limit constraints."); 00393 break; 00394 } 00395 00396 if(fabs(averageCostVelocity) < minimaThreshold && currentCostIter == -1 && !is_collision_free_ && parameters_->getAddRandomness()) 00397 { 00398 ROS_DEBUG("Detected local minima. Attempting to break out!"); 00399 int iter = 0; 00400 bool success = false; 00401 while(iter < 5 && !success) 00402 { 00403 performForwardKinematics(); 00404 double original_cost = getTrajectoryCost(); 00405 group_trajectory_backup_ = group_trajectory_.getTrajectory(); 00406 perturbTrajectory(); 00407 handleJointLimits(); 00408 updateFullTrajectory(); 00409 performForwardKinematics(); 00410 double new_cost = getTrajectoryCost(); 00411 iter ++; 00412 if(new_cost < original_cost) 00413 { 00414 ROS_DEBUG("Got out of minimum in %d iters!", iter); 00415 averageCostVelocity = 0.0; 00416 currentCostIter = 0; 00417 success = true; 00418 } 00419 else 00420 { 00421 group_trajectory_.getTrajectory() = group_trajectory_backup_; 00422 updateFullTrajectory(); 00423 currentCostIter = 0; 00424 averageCostVelocity = 0.0; 00425 success = false; 00426 } 00427 00428 } 00429 00430 if(!success) 00431 { 00432 ROS_DEBUG("Failed to exit minimum!"); 00433 } 00434 } 00435 else if(currentCostIter == -1) 00436 { 00437 currentCostIter = 0; 00438 averageCostVelocity = 0.0; 00439 } 00440 00441 if(parameters_->getAnimateEndeffector()) 00442 { 00443 animateEndeffector(); 00444 } 00445 00446 if(parameters_->getAnimatePath() && iteration_ % 25 == 0) 00447 { 00448 animatePath(); 00449 } 00450 00451 if(shouldBreakOut) 00452 { 00453 ROS_INFO("Trying collision free iteration %d", collision_free_iteration_); 00454 collision_free_iteration_++; 00455 if(collision_free_iteration_ > parameters_->getMaxIterationsAfterCollisionFree()) 00456 { 00457 break; 00458 } 00459 } 00460 00461 } 00462 00463 if(is_collision_free_) 00464 { 00465 ROS_INFO("Chomp path is collision free"); 00466 } 00467 else 00468 { 00469 ROS_ERROR("Chomp path is not collision free!"); 00470 } 00471 00472 if(parameters_->getAnimatePath()) 00473 { 00474 animatePath(); 00475 } 00476 00477 group_trajectory_.getTrajectory() = best_group_trajectory_; 00478 updateFullTrajectory(); 00479 00480 if(parameters_->getAnimatePath()) 00481 animatePath(); 00482 00483 ROS_INFO("Terminated after %d iterations, using path from iteration %d", iteration_, last_improvement_iteration_); 00484 ROS_INFO("Optimization core finished in %f sec", (ros::WallTime::now() - start_time).toSec()); 00485 } 00486 00487 bool ChompOptimizer::checkCurrentIterValidity() 00488 { 00489 JointTrajectory jointTrajectory; 00490 jointTrajectory.joint_names = joint_names_; 00491 jointTrajectory.header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId(); 00492 jointTrajectory.header.stamp = ros::Time::now(); 00493 Constraints goalConstraints; 00494 Constraints pathConstraints; 00495 ArmNavigationErrorCodes errorCode; 00496 vector<ArmNavigationErrorCodes> trajectoryErrorCodes; 00497 for(int i = 0; i < group_trajectory_.getNumPoints(); i++) 00498 { 00499 JointTrajectoryPoint point; 00500 for(int j = 0; j < group_trajectory_.getNumJoints(); j++) 00501 { 00502 point.positions.push_back(best_group_trajectory_(i, j)); 00503 } 00504 jointTrajectory.points.push_back(point); 00505 } 00506 00507 bool valid = collision_space_->isTrajectorySafe(jointTrajectory, goalConstraints, pathConstraints, planning_group_); 00508 /* 00509 bool valid = collision_space_->getCollisionModelsInterface()->isJointTrajectoryValid(*robot_state_, 00510 jointTrajectory, 00511 goalConstraints, 00512 pathConstraints, errorCode, 00513 trajectoryErrorCodes, false); 00514 */ 00515 00516 return valid; 00517 } 00518 00519 void ChompOptimizer::calculateSmoothnessIncrements() 00520 { 00521 for(int i = 0; i < num_joints_; i++) 00522 { 00523 joint_costs_[i].getDerivative(group_trajectory_.getJointTrajectory(i), smoothness_derivative_); 00524 smoothness_increments_.col(i) 00525 = -smoothness_derivative_.segment(group_trajectory_.getStartIndex(), num_vars_free_); 00526 } 00527 } 00528 00529 void ChompOptimizer::calculateCollisionIncrements() 00530 { 00531 double potential; 00532 double vel_mag_sq; 00533 double vel_mag; 00534 Vector3d potential_gradient; 00535 Vector3d normalized_velocity; 00536 Matrix3d orthogonal_projector; 00537 Vector3d curvature_vector; 00538 Vector3d cartesian_gradient; 00539 00540 00541 collision_increments_.setZero(num_vars_free_, num_joints_); 00542 00543 int startPoint = 0; 00544 int endPoint = free_vars_end_; 00545 00546 // In stochastic descent, simply use a random point in the trajectory, rather than all the trajectory points. 00547 // This is faster and guaranteed to converge, but it may take more iterations in the worst case. 00548 if(parameters_->getUseStochasticDescent()) 00549 { 00550 startPoint = (int)(((double)random() / (double)RAND_MAX)*(free_vars_end_ - free_vars_start_) + free_vars_start_); 00551 if(startPoint < free_vars_start_) startPoint = free_vars_start_; 00552 if(startPoint > free_vars_end_) startPoint = free_vars_end_; 00553 endPoint = startPoint; 00554 } 00555 else 00556 { 00557 startPoint = free_vars_start_; 00558 } 00559 00560 for(int i = startPoint; i <= endPoint; i++) 00561 { 00562 for(int j = 0; j < num_collision_points_; j++) 00563 { 00564 potential = collision_point_potential_[i][j]; 00565 00566 if(potential < 0.0001) 00567 continue; 00568 00569 potential_gradient = -collision_point_potential_gradient_[i][j]; 00570 00571 vel_mag = collision_point_vel_mag_[i][j]; 00572 vel_mag_sq = vel_mag * vel_mag; 00573 00574 // all math from the CHOMP paper: 00575 00576 normalized_velocity = collision_point_vel_eigen_[i][j] / vel_mag; 00577 orthogonal_projector = Matrix3d::Identity() - (normalized_velocity * normalized_velocity.transpose()); 00578 curvature_vector = (orthogonal_projector * collision_point_acc_eigen_[i][j]) / vel_mag_sq; 00579 cartesian_gradient = vel_mag * (orthogonal_projector * potential_gradient - potential * curvature_vector); 00580 00581 // pass it through the jacobian transpose to get the increments 00582 getJacobian(i, collision_point_pos_eigen_[i][j], collision_point_joint_names_[i][j] ,jacobian_); 00583 00584 if(parameters_->getUsePseudoInverse()) 00585 { 00586 calculatePseudoInverse(); 00587 collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_pseudo_inverse_ * cartesian_gradient; 00588 } 00589 else 00590 { 00591 collision_increments_.row(i - free_vars_start_).transpose() -= jacobian_.transpose() * cartesian_gradient; 00592 } 00593 00594 /* 00595 if(point_is_in_collision_[i][j]) 00596 { 00597 break; 00598 } 00599 */ 00600 } 00601 } 00602 //cout << collision_increments_ << endl; 00603 } 00604 00605 void ChompOptimizer::calculatePseudoInverse() 00606 { 00607 jacobian_jacobian_tranpose_ = jacobian_ * jacobian_.transpose() + MatrixXd::Identity(3, 3) 00608 * parameters_->getPseudoInverseRidgeFactor(); 00609 jacobian_pseudo_inverse_ = jacobian_.transpose() * jacobian_jacobian_tranpose_.inverse(); 00610 } 00611 00612 void ChompOptimizer::calculateTotalIncrements() 00613 { 00614 for(int i = 0; i < num_joints_; i++) 00615 { 00616 final_increments_.col(i) = parameters_->getLearningRate() * (joint_costs_[i].getQuadraticCostInverse() 00617 * (parameters_->getSmoothnessCostWeight() * smoothness_increments_.col(i) 00618 + parameters_->getObstacleCostWeight() * collision_increments_.col(i))); 00619 } 00620 00621 } 00622 00623 void ChompOptimizer::addIncrementsToTrajectory() 00624 { 00625 map<string, KinematicModel::JointModelGroup*> modelGroups = robot_model_->getJointModelGroupMap(); 00626 string group = planning_group_; 00627 const KinematicModel::JointModelGroup* modelGroup = modelGroups[group]; 00628 const vector<const KinematicModel::JointModel*>& jointModels = modelGroup->getJointModels(); 00629 00630 for(size_t i = 0; i < jointModels.size(); i++) 00631 { 00632 double scale = 1.0; 00633 double max = final_increments_.col(i).maxCoeff(); 00634 double min = final_increments_.col(i).minCoeff(); 00635 double max_scale = parameters_->getJointUpdateLimit() / fabs(max); 00636 double min_scale = parameters_->getJointUpdateLimit() / fabs(min); 00637 if(max_scale < scale) 00638 scale = max_scale; 00639 if(min_scale < scale) 00640 scale = min_scale; 00641 group_trajectory_.getFreeTrajectoryBlock().col(i) += scale * final_increments_.col(i); 00642 } 00643 //ROS_DEBUG("Scale: %f",scale); 00644 //group_trajectory_.getFreeTrajectoryBlock() += scale * final_increments_; 00645 } 00646 00647 void ChompOptimizer::updateFullTrajectory() 00648 { 00649 full_trajectory_->updateFromGroupTrajectory(group_trajectory_); 00650 } 00651 00652 void ChompOptimizer::debugCost() 00653 { 00654 double cost = 0.0; 00655 for(int i = 0; i < num_joints_; i++) 00656 cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i)); 00657 cout << "Cost = " << cost << endl; 00658 } 00659 00660 double ChompOptimizer::getTrajectoryCost() 00661 { 00662 return getSmoothnessCost() + getCollisionCost(); 00663 } 00664 00665 double ChompOptimizer::getSmoothnessCost() 00666 { 00667 double smoothness_cost = 0.0; 00668 // joint costs: 00669 for(int i = 0; i < num_joints_; i++) 00670 smoothness_cost += joint_costs_[i].getCost(group_trajectory_.getJointTrajectory(i)); 00671 00672 return parameters_->getSmoothnessCostWeight() * smoothness_cost; 00673 } 00674 00675 double ChompOptimizer::getCollisionCost() 00676 { 00677 double collision_cost = 0.0; 00678 00679 double worst_collision_cost = 0.0; 00680 worst_collision_cost_state_ = -1; 00681 00682 // collision costs: 00683 for(int i = free_vars_start_; i <= free_vars_end_; i++) 00684 { 00685 double state_collision_cost = 0.0; 00686 for(int j = 0; j < num_collision_points_; j++) 00687 { 00688 state_collision_cost += collision_point_potential_[i][j] * collision_point_vel_mag_[i][j]; 00689 } 00690 collision_cost += state_collision_cost; 00691 if(state_collision_cost > worst_collision_cost) 00692 { 00693 worst_collision_cost = state_collision_cost; 00694 worst_collision_cost_state_ = i; 00695 } 00696 } 00697 00698 return parameters_->getObstacleCostWeight() * collision_cost; 00699 } 00700 00701 void ChompOptimizer::computeJointProperties(int trajectoryPoint) 00702 { 00703 btTransform inverseWorldTransform = collision_space_->getInverseWorldTransform(*robot_state_); 00704 for(int j = 0; j < num_joints_; j++) 00705 { 00706 string jointName = joint_names_[j]; 00707 const KinematicState::JointState* jointState = robot_state_->getJointState(jointName); 00708 const KinematicModel::JointModel* jointModel = jointState->getJointModel(); 00709 const KinematicModel::RevoluteJointModel* revoluteJoint = dynamic_cast<const KinematicModel::RevoluteJointModel*>(jointModel); 00710 const KinematicModel::PrismaticJointModel* prismaticJoint = dynamic_cast<const KinematicModel::PrismaticJointModel*>(jointModel); 00711 00712 string parentLinkName = jointModel->getParentLinkModel()->getName(); 00713 string childLinkName = jointModel->getChildLinkModel()->getName(); 00714 btTransform jointTransform = 00715 robot_state_->getLinkState(parentLinkName)->getGlobalLinkTransform() 00716 * (robot_model_->getLinkModel(childLinkName)->getJointOriginTransform() 00717 * (robot_state_->getJointState(jointModel->getName())->getVariableTransform())); 00718 00719 00720 jointTransform = inverseWorldTransform * jointTransform; 00721 btVector3 axis; 00722 00723 00724 if(revoluteJoint != NULL) 00725 { 00726 axis = revoluteJoint->axis_; 00727 } 00728 else if(prismaticJoint != NULL) 00729 { 00730 axis = prismaticJoint->axis_; 00731 } 00732 00733 axis = jointTransform * axis; 00734 00735 joint_axes_[trajectoryPoint][j] = axis; 00736 joint_positions_[trajectoryPoint][j] = jointTransform.getOrigin(); 00737 } 00738 } 00739 00740 template<typename Derived> 00741 void ChompOptimizer::getJacobian(int trajectoryPoint, Vector3d& collision_point_pos, string& jointName, 00742 MatrixBase<Derived>& jacobian) const 00743 { 00744 for(int j = 0; j < num_joints_; j++) 00745 { 00746 if(isParent(jointName, joint_names_[j])) 00747 { 00748 btVector3 column = joint_axes_[trajectoryPoint][j].cross(btVector3(collision_point_pos(0), 00749 collision_point_pos(1), 00750 collision_point_pos(2)) 00751 - joint_positions_[trajectoryPoint][j]); 00752 00753 jacobian.col(j)[0] = column.x(); 00754 jacobian.col(j)[1] = column.y(); 00755 jacobian.col(j)[2] = column.z(); 00756 } 00757 else 00758 { 00759 jacobian.col(j)[0] = 0.0; 00760 jacobian.col(j)[1] = 0.0; 00761 jacobian.col(j)[2] = 0.0; 00762 } 00763 } 00764 } 00765 00766 void ChompOptimizer::handleJointLimits() 00767 { 00768 map<string, KinematicModel::JointModelGroup*> modelGroups = robot_model_->getJointModelGroupMap(); 00769 string group = planning_group_; 00770 KinematicModel::JointModelGroup* modelGroup = modelGroups[group]; 00771 00772 for(int joint = 0; joint < num_joints_; joint++) 00773 { 00774 const string& jointName = joint_names_[joint]; 00775 const KinematicModel::JointModel* jointModel = modelGroup->getJointModel(jointName); 00776 const KinematicModel::RevoluteJointModel* revoluteJoint = dynamic_cast<const KinematicModel::RevoluteJointModel*>(jointModel); 00777 00778 if(revoluteJoint->continuous_) 00779 { 00780 continue; 00781 } 00782 map<string, pair<double,double> > bounds = jointModel->getAllVariableBounds(); 00783 00784 double joint_max = -10000; 00785 double joint_min = 10000; 00786 00787 for(map<string,pair<double,double> >::iterator it = bounds.begin(); it != bounds.end(); it ++) 00788 { 00789 if(it->second.first < joint_min) 00790 { 00791 joint_min = it->second.first; 00792 } 00793 00794 if(it->second.second > joint_max) 00795 { 00796 joint_max = it->second.second; 00797 } 00798 } 00799 00800 00801 int count = 0; 00802 00803 bool violation = false; 00804 do 00805 { 00806 double max_abs_violation = 1e-6; 00807 double max_violation = 0.0; 00808 int max_violation_index = 0; 00809 violation = false; 00810 for(int i = free_vars_start_; i <= free_vars_end_; i++) 00811 { 00812 double amount = 0.0; 00813 double absolute_amount = 0.0; 00814 if(group_trajectory_(i, joint) > joint_max) 00815 { 00816 amount = joint_max - group_trajectory_(i, joint); 00817 absolute_amount = fabs(amount); 00818 } 00819 else if(group_trajectory_(i, joint) < joint_min) 00820 { 00821 amount = joint_min - group_trajectory_(i, joint); 00822 absolute_amount = fabs(amount); 00823 } 00824 if(absolute_amount > max_abs_violation) 00825 { 00826 max_abs_violation = absolute_amount; 00827 max_violation = amount; 00828 max_violation_index = i; 00829 violation = true; 00830 } 00831 } 00832 00833 if(violation) 00834 { 00835 int free_var_index = max_violation_index - free_vars_start_; 00836 double multiplier = max_violation / joint_costs_[joint].getQuadraticCostInverse()(free_var_index, 00837 free_var_index); 00838 group_trajectory_.getFreeJointTrajectoryBlock(joint) += multiplier 00839 * joint_costs_[joint].getQuadraticCostInverse().col(free_var_index); 00840 } 00841 if(++count > 10) 00842 break; 00843 } 00844 while(violation); 00845 } 00846 } 00847 00848 void ChompOptimizer::performForwardKinematics() 00849 { 00850 double invTime = 1.0 / group_trajectory_.getDiscretization(); 00851 double invTimeSq = invTime * invTime; 00852 00853 // calculate the forward kinematics for the fixed states only in the first iteration: 00854 int start = free_vars_start_; 00855 int end = free_vars_end_; 00856 if(iteration_ == 0) 00857 { 00858 start = 0; 00859 end = num_vars_all_ - 1; 00860 } 00861 00862 is_collision_free_ = true; 00863 00864 // for each point in the trajectory 00865 for(int i = start; i <= end; ++i) 00866 { 00867 // Set Robot state from trajectory point... 00868 setRobotStateFromPoint(group_trajectory_, i); 00869 computeJointProperties(i); 00870 state_is_in_collision_[i] = false; 00871 00872 vector<GradientInfo> gradients; 00873 collision_space_->getStateGradients(gradients); 00874 //Keep vars in scope 00875 { 00876 size_t j = 0; 00877 for(size_t g = 0; g < gradients.size(); g++) 00878 { 00879 GradientInfo& info = gradients[g]; 00880 00881 for(size_t k = 0; k < info.sphere_locations.size(); k++) 00882 { 00883 collision_point_pos_eigen_[i][j][0] = info.sphere_locations[k].x(); 00884 collision_point_pos_eigen_[i][j][1] = info.sphere_locations[k].y(); 00885 collision_point_pos_eigen_[i][j][2] = info.sphere_locations[k].z(); 00886 00887 collision_point_potential_[i][j] = getPotential(info.distances[k], info.sphere_radii[k], parameters_->getMinClearence()); 00888 collision_point_potential_gradient_[i][j][0] = info.gradients[k].x(); 00889 collision_point_potential_gradient_[i][j][1] = info.gradients[k].y(); 00890 collision_point_potential_gradient_[i][j][2] = info.gradients[k].z(); 00891 00892 point_is_in_collision_[i][j] = (info.distances[k] - info.sphere_radii[k] < info.sphere_radii[k]); 00893 00894 if(point_is_in_collision_[i][j]) 00895 { 00896 state_is_in_collision_[i] = true; 00897 is_collision_free_ = false; 00898 } 00899 j ++; 00900 } 00901 } 00902 } 00903 } 00904 00905 // now, get the vel and acc for each collision point (using finite differencing) 00906 for(int i = free_vars_start_; i <= free_vars_end_; i++) 00907 { 00908 for(int j = 0; j < num_collision_points_; j++) 00909 { 00910 collision_point_vel_eigen_[i][j] = Vector3d(0,0,0); 00911 collision_point_acc_eigen_[i][j] = Vector3d(0,0,0); 00912 for(int k = -DIFF_RULE_LENGTH / 2; k <= DIFF_RULE_LENGTH / 2; k++) 00913 { 00914 collision_point_vel_eigen_[i][j] += (invTime * DIFF_RULES[0][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i 00915 + k][j]; 00916 collision_point_acc_eigen_[i][j] += (invTimeSq * DIFF_RULES[1][k + DIFF_RULE_LENGTH / 2]) * collision_point_pos_eigen_[i 00917 + k][j]; 00918 } 00919 00920 // get the norm of the velocity: 00921 collision_point_vel_mag_[i][j] = collision_point_vel_eigen_[i][j].norm(); 00922 } 00923 } 00924 } 00925 00926 void ChompOptimizer::setRobotStateFromPoint(ChompTrajectory& group_trajectory, int i) 00927 { 00928 const MatrixXd::RowXpr& point = group_trajectory.getTrajectoryPoint(i); 00929 00930 vector<double> jointStates; 00931 for(int j = 0; j < group_trajectory.getNumJoints(); j ++) 00932 { 00933 jointStates.push_back(point(0,j)); 00934 } 00935 00936 ros::WallTime timer = ros::WallTime::now(); 00937 KinematicState::JointStateGroup* group = (KinematicState::JointStateGroup*)(robot_state_->getJointStateGroup(planning_group_)); 00938 group->setKinematicState(jointStates); 00939 timer = ros::WallTime::now(); 00940 collision_space_->setCurrentGroupState(*robot_state_); 00941 } 00942 00943 void ChompOptimizer::perturbTrajectory() 00944 { 00945 //int mid_point = (free_vars_start_ + free_vars_end_) / 2; 00946 if(worst_collision_cost_state_ < 0) 00947 return; 00948 int mid_point = worst_collision_cost_state_; 00949 getRandomState(robot_state_, planning_group_, random_state_); 00950 00951 // convert the state into an increment 00952 random_state_ -= group_trajectory_.getTrajectoryPoint(mid_point).transpose(); 00953 00954 // project the increment orthogonal to joint velocities 00955 group_trajectory_.getJointVelocities(mid_point, joint_state_velocities_); 00956 joint_state_velocities_.normalize(); 00957 random_state_ = (MatrixXd::Identity(num_joints_, num_joints_) - joint_state_velocities_ 00958 * joint_state_velocities_.transpose()) * random_state_; 00959 00960 int mp_free_vars_index = mid_point - free_vars_start_; 00961 for(int i = 0; i < num_joints_; i++) 00962 { 00963 group_trajectory_.getFreeJointTrajectoryBlock(i) 00964 += joint_costs_[i].getQuadraticCostInverse().col(mp_free_vars_index) * random_state_(i); 00965 } 00966 } 00967 00968 void ChompOptimizer::getRandomState(const KinematicState* currentState, const string& groupName, VectorXd& state_vec) 00969 { 00970 const vector<KinematicState::JointState*>& jointStates = 00971 currentState->getJointStateGroup(groupName)->getJointStateVector(); 00972 for(size_t i = 0; i < jointStates.size(); i++) 00973 { 00974 KinematicState::JointState* jointState = jointStates[i]; 00975 map<string, pair<double, double> > bounds = jointState->getJointModel()->getAllVariableBounds(); 00976 int j = 0; 00977 for(map<string, pair<double, double> >::iterator it = bounds.begin(); it != bounds.end(); it++) 00978 { 00979 double range = it->second.second - it->second.first; 00980 double randVal = jointState->getJointStateValues()[j] + (getRandomDouble() 00981 * (parameters_->getRandomJumpAmount()) - getRandomDouble() * (parameters_->getRandomJumpAmount())); 00982 00983 if(range == numeric_limits<double>::infinity()) 00984 { 00985 state_vec(i) = randVal; 00986 j++; 00987 continue; 00988 } 00989 if(randVal > it->second.second) 00990 { 00991 randVal = it->second.second; 00992 } 00993 else if(randVal < it->second.first) 00994 { 00995 randVal = it->second.first; 00996 } 00997 00998 state_vec(i) = randVal; 00999 j++; 01000 } 01001 } 01002 01003 } 01004 01005 void ChompOptimizer::getRandomMomentum() 01006 { 01007 if(is_collision_free_) 01008 random_momentum_.setZero(num_vars_free_, num_joints_); 01009 else 01010 for(int i = 0; i < num_joints_; ++i) 01011 { 01012 multivariate_gaussian_[i].sample(random_joint_momentum_); 01013 random_momentum_.col(i) = stochasticity_factor_ * random_joint_momentum_; 01014 } 01015 } 01016 01017 void ChompOptimizer::updateMomentum() 01018 { 01019 //double alpha = 1.0 - parameters_->getHmcStochasticity(); 01020 double eps = parameters_->getHmcDiscretization(); 01021 if(iteration_ > 0) 01022 momentum_ = (momentum_ + eps * final_increments_); 01023 else 01024 momentum_ = random_momentum_; 01025 //momentum_ = alpha * (momentum_ + eps*final_increments_) + sqrt(1.0-alpha*alpha)*random_momentum_; 01026 } 01027 01028 void ChompOptimizer::updatePositionFromMomentum() 01029 { 01030 double eps = parameters_->getHmcDiscretization(); 01031 group_trajectory_.getFreeTrajectoryBlock() += eps * momentum_; 01032 } 01033 01034 void ChompOptimizer::animatePath() 01035 { 01036 for(int i = free_vars_start_; i <= free_vars_end_; i++) 01037 { 01038 visualizeState(i); 01039 //ros::WallDuration(group_trajectory_.getDiscretization()).sleep(); 01040 ros::WallDuration(.05).sleep(); 01041 } 01042 } 01043 01044 void ChompOptimizer::animateEndeffector() 01045 { 01046 visualization_msgs::Marker msg; 01047 msg.points.resize(num_vars_free_); 01048 // int joint_index = planning_group_->chomp_joints_[num_joints_-1].kdl_joint_index_; 01049 int sn = (int)(num_collision_points_ - 1); 01050 for(int i = 0; i < num_vars_free_; ++i) 01051 { 01052 int j = i + free_vars_start_; 01053 msg.points[i].x = collision_point_pos_eigen_[j][sn][0]; 01054 msg.points[i].y = collision_point_pos_eigen_[j][sn][1]; 01055 msg.points[i].z = collision_point_pos_eigen_[j][sn][2]; 01056 } 01057 msg.header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId(); 01058 msg.header.stamp = ros::Time(); 01059 msg.ns = "chomp_endeffector"; 01060 msg.id = 0; 01061 msg.type = visualization_msgs::Marker::SPHERE_LIST; 01062 msg.action = visualization_msgs::Marker::ADD; 01063 double scale = 0.05; 01064 msg.scale.x = scale; 01065 msg.scale.y = scale; 01066 msg.scale.z = scale; 01067 msg.color.a = 0.6; 01068 msg.color.r = 0.5; 01069 msg.color.g = 1.0; 01070 msg.color.b = 0.3; 01071 vis_marker_pub_.publish(msg); 01072 ros::WallDuration(0.1).sleep(); 01073 01074 } 01075 01076 void ChompOptimizer::visualizeState(int index) 01077 { 01078 01079 visualization_msgs::MarkerArray msg; 01080 msg.markers.resize(num_collision_points_ + num_joints_); 01081 int num_arrows = 0; 01082 double potential_threshold = 1e-10; 01083 for(int i = 0; i < num_collision_points_; i++) 01084 { 01085 msg.markers[i].header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId(); 01086 msg.markers[i].header.stamp = ros::Time(); 01087 msg.markers[i].ns = "chomp_collisions"; 01088 msg.markers[i].id = i; 01089 msg.markers[i].type = visualization_msgs::Marker::SPHERE; 01090 msg.markers[i].action = visualization_msgs::Marker::ADD; 01091 msg.markers[i].pose.position.x = collision_point_pos_eigen_[index][i][0]; 01092 msg.markers[i].pose.position.y = collision_point_pos_eigen_[index][i][1]; 01093 msg.markers[i].pose.position.z = collision_point_pos_eigen_[index][i][2]; 01094 msg.markers[i].pose.orientation.x = 0.0; 01095 msg.markers[i].pose.orientation.y = 0.0; 01096 msg.markers[i].pose.orientation.z = 0.0; 01097 msg.markers[i].pose.orientation.w = 1.0; 01098 double scale = 0.1; 01099 msg.markers[i].scale.x = scale; 01100 msg.markers[i].scale.y = scale; 01101 msg.markers[i].scale.z = scale; 01102 msg.markers[i].color.a = 0.6; 01103 msg.markers[i].color.r = 0.5; 01104 msg.markers[i].color.g = 1.0; 01105 msg.markers[i].color.b = 0.3; 01106 if(collision_point_potential_[index][i] > potential_threshold) 01107 num_arrows++; 01108 } 01109 01110 vis_marker_array_pub_.publish(msg); 01111 01112 // publish arrows for distance field: 01113 msg.markers.resize(0); 01114 msg.markers.resize(num_collision_points_); 01115 for(int i = 0; i < num_collision_points_; i++) 01116 { 01117 msg.markers[i].header.frame_id = collision_space_->getCollisionModelsInterface()->getRobotFrameId(); 01118 msg.markers[i].header.stamp = ros::Time(); 01119 msg.markers[i].ns = "chomp_arrows"; 01120 msg.markers[i].id = i; 01121 msg.markers[i].type = visualization_msgs::Marker::ARROW; 01122 msg.markers[i].action = visualization_msgs::Marker::ADD; 01123 msg.markers[i].points.resize(2); 01124 msg.markers[i].points[0].x = collision_point_pos_eigen_[index][i](0); 01125 msg.markers[i].points[0].y = collision_point_pos_eigen_[index][i](1); 01126 msg.markers[i].points[0].z = collision_point_pos_eigen_[index][i](2); 01127 msg.markers[i].points[1] = msg.markers[i].points[0]; 01128 double scale = 0.25f; 01129 if(collision_point_potential_[index][i] <= potential_threshold) 01130 scale = 0.0; 01131 msg.markers[i].points[1].x += scale * collision_point_potential_gradient_[index][i](0); 01132 msg.markers[i].points[1].y += scale * collision_point_potential_gradient_[index][i](1); 01133 msg.markers[i].points[1].z += scale * collision_point_potential_gradient_[index][i](2); 01134 msg.markers[i].scale.x = 0.01; 01135 msg.markers[i].scale.y = 0.03; 01136 msg.markers[i].color.a = 0.5; 01137 msg.markers[i].color.r = 0.5; 01138 msg.markers[i].color.g = 0.5; 01139 msg.markers[i].color.b = 1.0; 01140 } 01141 vis_marker_array_pub_.publish(msg); 01142 01143 } 01144 01145 } // namespace chomp