Loading...
Searching...
No Matches
VectorFieldNonconservative.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Caleb Voss and Wilson Beebe
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 the 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/* Authors: Caleb Voss, Wilson Beebe */
36
37#include <fstream>
38
39#include <ompl/base/StateSpace.h>
40#include <ompl/base/objectives/VFUpstreamCriterionOptimizationObjective.h>
41#include <ompl/base/spaces/RealVectorStateSpace.h>
42#include <ompl/geometric/planners/rrt/RRTstar.h>
43#include <ompl/geometric/planners/rrt/VFRRT.h>
44#include <ompl/geometric/SimpleSetup.h>
45
46namespace ob = ompl::base;
47namespace og = ompl::geometric;
48
50Eigen::VectorXd field(const ob::State *state)
51{
53 Eigen::VectorXd v(2);
54 v[0] = x[1];
55 v[1] = -x[0];
56 v.normalize();
57 return v;
58}
59
60int main(int, char **)
61{
62 // construct the state space we are planning in
63 auto space(std::make_shared<ob::RealVectorStateSpace>(2));
64 auto si(std::make_shared<ob::SpaceInformation>(space));
65
66 ob::RealVectorBounds bounds(2);
67 bounds.setLow(-10);
68 bounds.setHigh(10);
69
70 space->as<ob::RealVectorStateSpace>()->setBounds(bounds);
71
72 // define a simple setup class
73 og::SimpleSetup ss(space);
74
75 // set state validity checking for this space
76 ss.setStateValidityChecker(std::make_shared<ob::AllValidStateValidityChecker>(si));
77
78 // create a start state
79 ob::ScopedState<> start(space);
80 start[0] = -5;
81 start[1] = -2;
82
83 // create a goal state
84 ob::ScopedState<> goal(space);
85 goal[0] = 5;
86 goal[1] = 2;
87
88 // set the start and goal states
89 ss.setStartAndGoalStates(start, goal, 0.1);
90
91 // initialize the planner
92 double explorationSetting = 0.7;
93 double lambda = 1;
94 unsigned int update_freq = 100;
95 ss.setPlanner(
96 std::make_shared<og::VFRRT>(ss.getSpaceInformation(), field, explorationSetting, lambda, update_freq));
97 ss.setup();
98
99 // attempt to solve the problem
100 ob::PlannerStatus solved = ss.solve(10.0);
101
102 if (solved)
103 {
105 std::cout << "Found solution.\n";
106 else
107 std::cout << "Found approximate solution.\n";
108
109 // Set up to write the path
110 std::ofstream f("vfrrt-nonconservative.path");
111 ompl::geometric::PathGeometric p = ss.getSolutionPath();
112 p.interpolate();
113 auto upstream(std::make_shared<ob::VFUpstreamCriterionOptimizationObjective>(ss.getSpaceInformation(), field));
114 p.printAsMatrix(f);
115 std::cout << "Total upstream cost: " << p.cost(upstream) << "\n";
116 }
117 else
118 std::cout << "No solution found.\n";
119
120 return 0;
121}
The lower and upper bounds for an Rn space.
A state space representing Rn. The distance function is the L2 norm.
Definition of a scoped state.
Definition ScopedState.h:57
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
Definition of a geometric path.
void interpolate(unsigned int count)
Insert a number of states in a path so that the path is made up of exactly count states....
virtual void printAsMatrix(std::ostream &out) const
Print the path as a real-valued matrix where the i-th row represents the i-th state along the path....
base::Cost cost(const base::OptimizationObjectivePtr &obj) const override
The sum of the costs for the sequence of segments that make up the path, computed using OptimizationO...
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace contains code that is specific to planning under geometric constraints.
A class to store the exit status of Planner::solve().
@ EXACT_SOLUTION
The planner found an exact solution.