void ContactOptimizeMultipath(const char* robfile,const char* pathfile,const char* settingsfile = NULL) { ContactOptimizeSettings settings; if(settingsfile != NULL) { if(!settings.read(settingsfile)) { printf("Unable to read settings file %s\n",settingsfile); return; } } Real xtol=Real(settings["xtol"]); int numdivs = int(settings["numdivs"]); bool ignoreForces = bool(settings["ignoreForces"]); Real torqueRobustness = Real(settings["torqueRobustness"]); Real frictionRobustness = Real(settings["frictionRobustness"]); Real forceRobustness = Real(settings["forceRobustness"]); string outputPath; settings["outputPath"].as(outputPath); Real outputDt = Real(settings["outputDt"]); Robot robot; if(!robot.Load(robfile)) { printf("Unable to load robot file %s\n",robfile); return; } MultiPath path; if(!path.Load(pathfile)) { printf("Unable to load path file %s\n",pathfile); return; } //double check friction for(size_t i=0;i<path.sections.size();i++) { Stance s; path.GetStance(s,i); bool changed = false; int k=0; int numContacts = 0; for(Stance::iterator h=s.begin();h!=s.end();h++,k++) { numContacts += (int)h->second.contacts.size(); for(size_t j=0;j<h->second.contacts.size();j++) if(h->second.contacts[j].kFriction <= 0) { if(!changed) printf("Warning, contact %d of hold %d has invalid friction %g, setting to 0.5\n",j,k,h->second.contacts[j].kFriction); h->second.contacts[j].kFriction = 0.5; changed = true; } } path.SetStance(s,i); if(numContacts == 0 && !ignoreForces && robot.joints[0].type == RobotJoint::Floating) { printf("Warning, no contacts given in stance %d for floating-base robot\n",i); printf("Should set ignoreForces = true in trajopt.settings if you wish\n"); printf("to ignore contact force constraints.\n"); printf("Press enter to continue...\n"); getchar(); } } TimeScaledBezierCurve opttraj; if(ignoreForces) { bool res=GenerateAndTimeOptimizeMultiPath(robot,path,xtol,outputDt); if(!res) { printf("Time optimization failed\n"); return; } Assert(path.HasTiming()); cout<<"Saving dynamically optimized path to "<<outputPath<<endl; ofstream out(outputPath.c_str(),ios::out); for(size_t i=0;i<path.sections.size();i++) { for(size_t j=0;j<path.sections[i].milestones.size();j++) out<<path.sections[i].times[j]<<"\t"<<path.sections[i].milestones[j]<<endl; } out.close(); } else { bool res=ContactOptimizeMultipath(robot,path,xtol, numdivs,opttraj, torqueRobustness, frictionRobustness, forceRobustness); if(!res) { printf("Time optimization failed\n"); return; } RobotCSpace cspace(robot); for(size_t i=0;i<opttraj.path.segments.size();i++) { opttraj.path.segments[i].space = &cspace; opttraj.path.segments[i].manifold = &cspace; } vector<Config> milestones; opttraj.GetDiscretizedPath(outputDt,milestones); cout<<"Saving dynamically optimized path to "<<outputPath<<endl; ofstream out(outputPath.c_str(),ios::out); for(size_t i=0;i<milestones.size();i++) { out<<i*outputDt<<"\t"<<milestones[i]<<endl; } out.close(); printf("Plotting vel/acc constraints to trajopt_plot.csv...\n"); opttraj.Plot("trajopt_plot.csv",robot.velMin,robot.velMax,-1.0*robot.accMax,robot.accMax); } }
bool GenerateAndTimeOptimizeMultiPath(Robot& robot,MultiPath& multipath,Real xtol,Real dt) { Timer timer; vector<GeneralizedCubicBezierSpline > paths; if(!InterpolateConstrainedMultiPath(robot,multipath,paths,xtol)) return false; printf("Generated interpolating path in time %gs\n",timer.ElapsedTime()); RobotCSpace cspace(robot); RobotGeodesicManifold manifold(robot); for(size_t i=0;i<multipath.sections.size();i++) { for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].space = &cspace; paths[i].segments[j].manifold = &manifold; } for(int iters=0;iters<gNumTimescaleBisectIters;iters++) paths[i].Bisect(); } #if SAVE_INTERPOLATING_CURVES int index=0; printf("Saving sections, element %d to section_x_bezier.csv\n",index); for(size_t i=0;i<paths.size();i++) { { stringstream ss; ss<<"section_"<<i<<"_bezier.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"duration,x0,x1,x2,x3"<<endl; for(size_t j=0;j<paths[i].segments.size();j++) { out<<paths[i].durations[j]<<","<<paths[i].segments[j].x0[index]<<","<<paths[i].segments[j].x1[index]<<","<<paths[i].segments[j].x2[index]<<","<<paths[i].segments[j].x3[index]<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_vel.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"v(0),v(0.5),v(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Deriv(0,temp); temp /= paths[i].durations[j]; out<<temp[index]; paths[i].segments[j].Deriv(0.5,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; paths[i].segments[j].Deriv(1,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; out<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_acc.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"a(0),a(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Accel(0,temp); temp /= Sqr(paths[i].durations[j]); out<<temp[index]; paths[i].segments[j].Accel(1,temp); temp /= Sqr(paths[i].durations[j]); out<<","<<temp[index]; out<<endl; } out.close(); } } #endif //SAVE_INTERPOLATING_CURVES #if SAVE_LORES_INTERPOLATING_CURVES paths.clear(); if(!InterpolateConstrainedMultiPath(robot,multipath,paths,xtol*2.0)) return false; for(size_t i=0;i<multipath.sections.size();i++) { for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].space = &cspace; paths[i].segments[j].manifold = &manifold; } } for(size_t i=0;i<paths.size();i++) { { stringstream ss; ss<<"section_"<<i<<"_bezier_x2.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"duration,x0,x1,x2,x3"<<endl; for(size_t j=0;j<paths[i].segments.size();j++) { out<<paths[i].durations[j]<<","<<paths[i].segments[j].x0[index]<<","<<paths[i].segments[j].x1[index]<<","<<paths[i].segments[j].x2[index]<<","<<paths[i].segments[j].x3[index]<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_vel_x2.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"v(0),v(0.5),v(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Deriv(0,temp); temp /= paths[i].durations[j]; out<<temp[index]; paths[i].segments[j].Deriv(0.5,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; paths[i].segments[j].Deriv(1,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; out<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_acc_x2.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"a(0),a(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Accel(0,temp); temp /= Sqr(paths[i].durations[j]); out<<temp[index]; paths[i].segments[j].Accel(1,temp); temp /= Sqr(paths[i].durations[j]); out<<","<<temp[index]; out<<endl; } out.close(); } } paths.clear(); if(!InterpolateConstrainedMultiPath(robot,multipath,paths,xtol*4.0)) return false; for(size_t i=0;i<multipath.sections.size();i++) { for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].space = &cspace; paths[i].segments[j].manifold = &manifold; } } for(size_t i=0;i<paths.size();i++) { { stringstream ss; ss<<"section_"<<i<<"_bezier_x4.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"duration,x0,x1,x2,x3"<<endl; for(size_t j=0;j<paths[i].segments.size();j++) { out<<paths[i].durations[j]<<","<<paths[i].segments[j].x0[index]<<","<<paths[i].segments[j].x1[index]<<","<<paths[i].segments[j].x2[index]<<","<<paths[i].segments[j].x3[index]<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_vel_x4.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"v(0),v(0.5),v(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Deriv(0,temp); temp /= paths[i].durations[j]; out<<temp[index]; paths[i].segments[j].Deriv(0.5,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; paths[i].segments[j].Deriv(1,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; out<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_acc_x4.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"a(0),a(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Accel(0,temp); temp /= Sqr(paths[i].durations[j]); out<<temp[index]; paths[i].segments[j].Accel(1,temp); temp /= Sqr(paths[i].durations[j]); out<<","<<temp[index]; out<<endl; } out.close(); } } paths.clear(); if(!InterpolateConstrainedMultiPath(robot,multipath,paths,xtol*8.0)) return false; for(size_t i=0;i<multipath.sections.size();i++) { for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].space = &cspace; paths[i].segments[j].manifold = &manifold; } } for(size_t i=0;i<paths.size();i++) { { stringstream ss; ss<<"section_"<<i<<"_bezier_x8.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"duration,x0,x1,x2,x3"<<endl; for(size_t j=0;j<paths[i].segments.size();j++) { out<<paths[i].durations[j]<<","<<paths[i].segments[j].x0[index]<<","<<paths[i].segments[j].x1[index]<<","<<paths[i].segments[j].x2[index]<<","<<paths[i].segments[j].x3[index]<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_vel_x8.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"v(0),v(0.5),v(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Deriv(0,temp); temp /= paths[i].durations[j]; out<<temp[index]; paths[i].segments[j].Deriv(0.5,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; paths[i].segments[j].Deriv(1,temp); temp /= paths[i].durations[j]; out<<","<<temp[index]; out<<endl; } out.close(); } { stringstream ss; ss<<"section_"<<i<<"_bezier_acc_x8.csv"; ofstream out(ss.str().c_str(),ios::out); out<<"a(0),a(1)"<<endl; Vector temp; for(size_t j=0;j<paths[i].segments.size();j++) { paths[i].segments[j].Accel(0,temp); temp /= Sqr(paths[i].durations[j]); out<<temp[index]; paths[i].segments[j].Accel(1,temp); temp /= Sqr(paths[i].durations[j]); out<<","<<temp[index]; out<<endl; } out.close(); } } #endif //SAVE_LORES_INTERPOLATING_CURVES //concatenate sections into a single curve TimeScaledBezierCurve traj; vector<int> edgeToSection,sectionEdges(1,0); for(size_t i=0;i<multipath.sections.size();i++) { traj.path.Concat(paths[i]); for(size_t j=0;j<paths[i].segments.size();j++) edgeToSection.push_back((int)i); sectionEdges.push_back(sectionEdges.back()+(int)paths[i].segments.size()); } timer.Reset(); bool res=traj.OptimizeTimeScaling(robot.velMin,robot.velMax,-1.0*robot.accMax,robot.accMax); if(!res) { printf("Failed to optimize time scaling\n"); return false; } else { printf("Optimized into a path with duration %g, (took %gs)\n",traj.EndTime(),timer.ElapsedTime()); } double T = traj.EndTime(); int numdivs = (int)Ceil(T/dt); printf("Discretizing at time resolution %g\n",T/numdivs); numdivs++; Vector x,v; int sCur = -1; for(int i=0;i<numdivs;i++) { Real t=T*Real(i)/Real(numdivs-1); int trajEdge = traj.timeScaling.TimeToSegment(t); if(trajEdge == (int)edgeToSection.size()) trajEdge--; //end of path Assert(trajEdge < (int)edgeToSection.size()); int s=edgeToSection[trajEdge]; if(s < sCur) { fprintf(stderr,"Strange: edge index is going backward? %d -> %d\n",sCur,s); fprintf(stderr," time %g, division %d, traj segment %d\n",t,i,trajEdge); } Assert(s - sCur >=0); while(sCur < s) { //close off the current section and add a new one Real switchTime=traj.timeScaling.times[sectionEdges[sCur+1]]; Assert(switchTime <= t); traj.Eval(switchTime,x); traj.Deriv(switchTime,v); if(sCur >= 0) { multipath.sections[sCur].times.push_back(switchTime); multipath.sections[sCur].milestones.push_back(x); multipath.sections[sCur].velocities.push_back(v); } multipath.sections[sCur+1].milestones.resize(0); multipath.sections[sCur+1].velocities.resize(0); multipath.sections[sCur+1].times.resize(0); multipath.sections[sCur+1].milestones.push_back(x); multipath.sections[sCur+1].velocities.push_back(v); multipath.sections[sCur+1].times.push_back(switchTime); sCur++; } if(t == multipath.sections[s].times.back()) continue; traj.Eval(t,x); traj.Deriv(t,v); multipath.sections[s].times.push_back(t); multipath.sections[s].milestones.push_back(x); multipath.sections[s].velocities.push_back(v); } #if DO_TEST_TRIANGULAR timer.Reset(); TimeScaledBezierCurve trajTri; Real Ttrap = 0; printf("%d paths?\n",paths.size()); for(size_t i=0;i<paths.size();i++) Ttrap += OptimalTriangularTimeScaling(paths[i],robot.velMin,robot.velMax,-1.0*robot.accMax,robot.accMax,trajTri); printf("Optimal trapezoidal time scaling duration %g, calculated in %gs\n",Ttrap,timer.ElapsedTime()); printf("Saving plot to opt_tri_multipath.csv\n"); trajTri.Plot("opt_tri_multipath.csv",robot.velMin,robot.velMax,-1.0*robot.accMax,robot.accMax); #endif // DO_TEST_TRAPEZOIDAL #if DO_CHECK_BOUNDS CheckBounds(robot,traj,dt); #endif // DO_CHECK_BOUNDS #if DO_SAVE_PLOT printf("Saving plot to opt_multipath.csv\n"); traj.Plot("opt_multipath.csv",robot.velMin,robot.velMax,-1.0*robot.accMax,robot.accMax); #endif //DO_SAVE_PLOT #if DO_SAVE_LIMITS SaveLimits(robot,traj,dt,"opt_multipath_limits.csv"); #endif // DO_SAVE_LIMITS { multipath.settings.set("resolution",xtol); multipath.settings.set("program","GenerateAndTimeOptimizeMultiPath"); } return true; }
int main(int argc,const char** argv) { if(argc < 5) { printf("USAGE: timeopt spline limits gridRes dt\n"); printf(" Optimizes the time scaling of the cubic spline 'spline' under\n"); printf(" velocity/acceleration limits in the file 'limits'.\n"); printf(" The time-scaling domain is split into gridRes points.\n"); printf(" The output trajectory is a list of time/milestone pairs\n"); printf(" discretized at timestep dt.\n"); return 0; } TimeScaledBezierCurve output; { ifstream in(argv[1],ios::in); if(!output.path.Load(in)) { printf("Unable to load spline file %s\n",argv[1]); return 1; } } Vector vmin,vmax,amin,amax; { ifstream in(argv[2],ios::in); if(!in) { printf("Unable to load limits file %s\n",argv[2]); return 1; } in >> vmin >> vmax >> amin >> amax; if(!in) { printf("Error loading limits file %s\n",argv[2]); return 1; } } for(size_t i=0;i<output.path.segments.size();i++) { if(output.path.segments[i].x0.n != output.path.segments[0].x0.n) { printf("Invalid milestone size on segment %d: %d vs %d\n",i,output.path.segments[i].x0.n,output.path.segments[0].x0.n); return 1; } if(output.path.segments[i].x1.n != output.path.segments[0].x0.n) { printf("Invalid milestone size on segment %d: %d vs %d\n",i,output.path.segments[i].x1.n,output.path.segments[0].x0.n); return 1; } if(output.path.segments[i].x2.n != output.path.segments[0].x0.n) { printf("Invalid milestone size on segment %d: %d vs %d\n",i,output.path.segments[i].x2.n,output.path.segments[0].x0.n); return 1; } if(output.path.segments[i].x3.n != output.path.segments[0].x0.n) { printf("Invalid milestone size on segment %d: %d vs %d\n",i,output.path.segments[i].x3.n,output.path.segments[0].x0.n); return 1; } } if(vmin.n != output.path.segments[0].x0.n) { printf("Invalid length of limits: %d vs %d\n",vmin.n,output.path.segments[0].x0.n); return 1; } int gridRes; Real dt; gridRes = atoi(argv[3]); dt = atof(argv[4]); if((int)output.path.segments.size() < gridRes) { GeneralizedCubicBezierSpline path; path.segments.reserve(gridRes+output.path.segments.size()); path.durations.reserve(gridRes+output.path.segments.size()); Config xp,vp,xn,vn; Real T = output.path.TotalTime(); for(size_t i=0;i<output.path.segments.size();i++) { int n = (int)Ceil(gridRes*(output.path.durations[i]/T)); if(n <= 0) { printf("Error: curve segment %d has nonpositive duration?\n",i); return 1; } //split segment[i] into n pieces Real divScale = 1.0/Real(n); xp = output.path.segments[i].x0; output.path.segments[i].Deriv(0,vp); for(int j=0;j<n;j++) { Real u2=Real(j+1)/Real(n); output.path.segments[i].Eval(u2,xn); output.path.segments[i].Deriv(u2,vn); path.segments.resize(path.segments.size()+1); path.durations.push_back(divScale*output.path.durations[i]); path.segments.back().x0 = xp; path.segments.back().x3 = xn; path.segments.back().SetNaturalTangents(vp*divScale,vn*divScale); swap(xp,xn); swap(vp,vn); } } output.path = path; } Timer timer; if(!output.OptimizeTimeScaling(vmin,vmax,amin,amax)) { printf("Error: OptimizeTimeScaling failed\n"); return 1; } Real elapsedTime = timer.ElapsedTime(); printf("Optimized duration %g, time %g\n",output.EndTime(),elapsedTime); vector<Vector> milestones; output.GetDiscretizedPath(dt,milestones); for(size_t i=0;i<milestones.size();i++) cout<<dt*i<<"\t"<<milestones[i]<<endl;; printf("Saving time scaling to timeopt_plot.csv\n"); output.Plot("timeopt_plot.csv",vmin,vmax,amin,amax,1.0/Real(gridRes)); return 0; }