static void path_cleanup( struct aa_rx_mp *mp, ompl::geometric::PathGeometric &path ) { amino::sgSpaceInformation::Ptr &si = mp->space_information; if( mp->simplify ) { ompl::geometric::PathSimplifier ps(si); int n = (int)path.getStateCount(); path.interpolate(n*10); for( int i = 0; i < 10; i ++ ) { ps.reduceVertices(path); ps.collapseCloseVertices(path); ps.shortcutPath(path); } ps.smoothBSpline(path, 3, path.length()/100.0); } }
EReturn OMPLsolver::getSimplifiedPath(ompl::geometric::PathGeometric &pg, Eigen::MatrixXd & traj, ob::PlannerTerminationCondition &ptc) { if (smooth_->data) { HIGHLIGHT("Simplifying solution"); int original_cnt = pg.getStateCount(); ros::Time start = ros::Time::now(); //ompl_simple_setup_->simplifySolution(d); // Lets do our own simplifier ~:) if (original_cnt >= 3) { og::PathSimplifierPtr psf_ = ompl_simple_setup_->getPathSimplifier(); const ob::SpaceInformationPtr &si = ompl_simple_setup_->getSpaceInformation(); bool tryMore = false; if (ptc == false) tryMore = psf_->reduceVertices(pg); if (ptc == false) psf_->collapseCloseVertices(pg); int times = 0; while (tryMore && ptc == false) { tryMore = psf_->reduceVertices(pg); times++; } if (si->getStateSpace()->isMetricSpace()) { if (ptc == false) tryMore = psf_->shortcutPath(pg); else tryMore = false; times = 0; while (tryMore && ptc == false) { tryMore = psf_->shortcutPath(pg); times++; } } std::vector<ob::State*> &states = pg.getStates(); // Calculate number of states required unsigned int length = 0; const int n1 = states.size() - 1; for (int i = 0; i < n1; ++i) length += si->getStateSpace()->validSegmentCount(states[i], states[i + 1]); // // Forward reducing // HIGHLIGHT("States before forward reducing: "<<pg.getStateCount()); // pg.interpolate(length); // // bool need_backward = true; // for (int i = states.size() - 1; i > 0; i--) // { // if (si->checkMotion(states[0], states[i])) // { // ob::State *start = si->cloneState(states[0]); // pg.keepAfter(states[i]); // pg.prepend(start); // need_backward = (i == states.size() - 1) ? false : true; // break; // } // } // // // Backward reducing // ob::State *mid; // if (need_backward) // { // HIGHLIGHT("States before backward reducing: "<<pg.getStateCount()); // pg.interpolate(length); // for (int i = 1; i < states.size(); i++) // { // if (si->checkMotion(states[states.size() - 1], states[i])) // { // ob::State *goal = si->cloneState(states[states.size() - 1]); // pg.keepBefore(states[i]); // pg.append(goal); // mid = si->cloneState(states[i]); // break; // } // } // } pg.interpolate(length); } // if (ompl_simple_setup_->haveSolutionPath()) // { // pg.interpolate(); // } HIGHLIGHT_NAMED("OMPLSolver", "Simplification took "<<ros::Duration(ros::Time::now()-start).toSec()<<"sec. States: "<<original_cnt<<"->"<<pg.getStateCount()); } convertPath(pg, traj); return SUCCESS; }