PlannerProgressProperties.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Rice University
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 Rice University 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 /* Author: Luis G. Torres */
36 
37 #include <ompl/geometric/SimpleSetup.h>
38 #include <ompl/tools/benchmark/Benchmark.h>
39 #include <ompl/base/spaces/RealVectorStateSpace.h>
40 #include <ompl/geometric/planners/rrt/RRTstar.h>
41 
42 namespace ob = ompl::base;
43 namespace og = ompl::geometric;
44 
46 //
47 // In this demo we define a simple 2D planning problem to get from
48 // (0,0) to (1,1) without obstacles. We're interested in collecting
49 // data over the execution of a planner using the Benchmark class.
50 //
51 // This program will output two files: a .console file, and a .log
52 // file. You can generate plots in a file called "plot.pdf" from this
53 // experiment using the ompl/scripts/ompl_benchmark_statistics.py
54 // script and the .log file like so:
55 //
56 // python path/to/ompl/scripts/ompl_benchmark_statistics.py <your_log_filename>.log -p plot.pdf
57 //
58 // Toward the bottom of the generated plot.pdf file, you'll see plots
59 // for how various properties change, on average, during planning
60 // runs.
61 int main(int, char**)
62 {
63  auto space(std::make_shared<ob::RealVectorStateSpace>(2));
64  space->setBounds(0, 1);
65  og::SimpleSetup ss(space);
66 
67  // Set our robot's starting state to be the bottom-left corner of
68  // the environment, or (0,0).
69  ob::ScopedState<> start(space);
70  start->as<ob::RealVectorStateSpace::StateType>()->values[0] = 0.0;
71  start->as<ob::RealVectorStateSpace::StateType>()->values[1] = 0.0;
72 
73  // Set our robot's goal state to be the top-right corner of the
74  // environment, or (1,1).
75  ob::ScopedState<> goal(space);
76  goal->as<ob::RealVectorStateSpace::StateType>()->values[0] = 1.0;
77  goal->as<ob::RealVectorStateSpace::StateType>()->values[1] = 1.0;
78 
79  // Goal tolerance is 0.05
80  ss.setStartAndGoalStates(start, goal, 0.05);
81 
82  // Create a new Benchmark object and set the RRTstar algorithm as
83  // the planner. We're using RRTstar because currently, only the
84  // RRTstar algorithm reports interesting planner progress
85  // properties.
86  ompl::tools::Benchmark b(ss, "my experiment");
87  auto rrt(std::make_shared<og::RRTstar>(ss.getSpaceInformation()));
88  rrt->setName("rrtstar");
89 
90  // We disable goal biasing so that the straight-line path doesn't
91  // get found immediately. We want to demonstrate the steady
92  // downward trend in path cost that characterizes RRTstar.
93  rrt->setGoalBias(0.0);
94 
95  b.addPlanner(rrt);
96 
97  // Here we specify options for this benchmark. Maximum time spent
98  // per planner execution is 2.0 seconds, maximum memory is 100MB,
99  // number of planning runs is 50, planner progress properties will
100  // be queried every 0.01 seconds, and a progress bar will be
101  // displayed to show how the benchmarking is going.
103  req.maxTime = 2.0;
104  req.maxMem = 100;
105  req.runCount = 50;
106  req.timeBetweenUpdates = 0.01;
107  req.displayProgress = true;
108  b.benchmark(req);
109 
110  b.saveResultsToFile();
111 
112  return 0;
113 
114 }
This namespace contains code that is specific to planning under geometric constraints.
Definition: GeneticSearch.h:79
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Create the set of classes typically needed to solve a geometric problem.
Definition: SimpleSetup.h:126
ompl::base::State StateType
Define the type of state allocated by this space.
Definition: StateSpace.h:142
unsigned int runCount
the number of times to run each planner; 100 by default If set to 0, then run each planner as many ti...
Definition: Benchmark.h:276
bool displayProgress
flag indicating whether progress is to be displayed or not; true by default
Definition: Benchmark.h:283
Representation of a benchmark request.
Definition: Benchmark.h:252
Benchmark a set of planners on a problem instance.
Definition: Benchmark.h:112
double maxMem
the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default
Definition: Benchmark.h:272
Definition of a scoped state.
Definition: ScopedState.h:120
double timeBetweenUpdates
When collecting time-varying data from a planner during its execution, the planner's progress will be...
Definition: Benchmark.h:280
double maxTime
the maximum amount of time a planner is allowed to run (seconds); 5.0 by default
Definition: Benchmark.h:269