From: Mark M. <mm...@ri...> - 2018-09-11 13:41:34
|
Hi Aswin, No, it wouldn’t be a Dubins vehicle anymore. Of course, you can copy the Dubins-related code and make your own state space. Best, Mark > On Sep 11, 2018, at 2:45 AM, Aswin Thomas <asw...@gm...> wrote: > > Mark, > Would it be possible to force the Dubins curve to be generated only towards say left direction i.e. for a robot that is only capable of turning left but not right. > > Aswin > > On Wed, Jul 2, 2014 at 10:12 PM Mark Moll <mm...@ri...> wrote: > Hi Aswin, > > My answers to your questions are below. > > On Jul 1, 2014, at 9:38 PM, Aswin Thomas <asw...@gm...> wrote: > > > Hi all, > > I am new to OMPL and need your help on how to implement planning for a car-like robot. Below is the code I put together for a kinematic car after looking at the tutorials. > > > > I would like to know a few things: > > > > 1) I am assuming planning with controls is the way to obtain trajectory planning in sampling based planning. How can I make this code better? > > Most of the control-based planners can take advantage of a steering function if you implement one. We have made that a little easier very recently (as in: it’s in our bitbucket/github repositories, but not in the latest release). For the particular system of interest you need to implement a StatePropagator-derived class that, in addition to the propagate method, implements a steer() method and a canSteer() method which simply returns true. If you use, e.g., ompl::control::RRT as your planner it will automatically use your steer method. > > > 2) I understand there is no optimal planning with controls in OMPL (e.g. using RRTstar). Is this implementation possible and if so, how do I go about doing it. > > It’s definitely possible. See, e.g.: > http://arxiv.org/pdf/1205.5088.pdf > http://ares.lids.mit.edu/papers/Karaman.Frazzoli.ICRA13.pdf > http://www.pracsyslab.org/node/123 > > I haven’t checked if there any practical hurdles in implementing these algorithms using OMPL. > > > 3) I only obtain a single path solution. Why does it not return multiple solutions? The C-space seems to be completely explored > > The planner used simply terminates after the first solution is found. While the rest of the C-space may have been explored, the paths going through the rest of the C-space may not lead to a solution (i.e., they don’t reach the goal). > > > > Code: > > ob::StateSpacePtr space(new ob::DubinsStateSpace()); > > This is an interesting design choice. It will make your car more likely to find paths where the car drives forward but doesn’t prevent if from driving backwards (unless your KinematicCarODE doesn’t allow that either). The rest of the code looks fine to me. > > > ob::RealVectorBounds bounds(2); bounds.setLow(-5); bounds.setHigh(11); // set the bounds for the R^2 part of SE(2) > > space->as()->setBounds(bounds); > > > > oc::ControlSpacePtr cspace(new oc::RealVectorControlSpace(space,2)); // create a control space > > ob::RealVectorBounds cbounds(2); // set the bounds for the control space > > cbounds.setLow(0,0.0); cbounds.setHigh(0,2.0); //set forward velocity bounds > > cbounds.setLow(1,-1.5); cbounds.setHigh(1,1.0); //set angular velocity bounds > > cspace->as()->setBounds(cbounds); > > > > oc::SimpleSetup ss(cspace); // define a simple setup class > > oc::SpaceInformationPtr si(ss.getSpaceInformation()); > > ss.setStateValidityChecker(boost::bind(&isStateValid,si.get(),_1)); // set state validity checking for this space > > > > oc::ODESolverPtr odeSolver(new oc::ODEBasicSolver<> (si, &KinematicCarODE)); > > ss.setStatePropagator(ompl::control::ODESolver::getStatePropagator(odeSolver)); > > > > ob::ScopedState start(space); // create a start state > > start->setX(0.0); start->setY(0.0); start->setYaw(0.0); > > ob::ScopedState goal(space); // create a goal state; use the hard way to set the elements > > goal->setX(10.0); goal->setY(10.0); goal->setYaw(0.0); > > ss.setStartAndGoalStates(start, goal, 0.05); > > > > //set planner type > > si->setMinMaxControlDuration(1,20); > > si->setPropagationStepSize(0.06); > > ob::PlannerPtr planner(new oc::RRT(si)); > > ss.setPlanner(planner); > > > > ob::PlannerStatus solved = ss.solve(50); // attempt to solve the problem within 50 second of planning time > > > > oc::PathControl& path(ss.getSolutionPath()); > > path.interpolate(); > > ob::PlannerData data(ss.getSpaceInformation()); > > ss.getPlanner()->getPlannerData(data); > > std::vector allPaths; > > allPaths = ss.getProblemDefinition()->getSolutions(); > > ROS_INFO(“%lu solution(s) found”,allPaths.size()); > > > > > > > > Regards > > > > Aswin > > > > ------------------------------------------------------------------------------ > > Open source business process management suite built on Java and Eclipse > > Turn processes into business applications with Bonita BPM Community Edition > > Quickly connect people, data, and systems into organized workflows > > Winner of BOSSIE, CODIE, OW2 and Gartner awards > > http://p.sf.net/sfu/Bonitasoft_______________________________________________ > > ompl-users mailing list > > omp...@li... > > https://lists.sourceforge.net/lists/listinfo/ompl-users > > -- > Mark Moll > > > |