/usr/share/ompl/demos/RigidBodyPlanningWithIK.cpp is in ompl-demos 1.0.0+ds2-1build1.
This file is owned by root:root, with mode 0o644.
The actual contents of the file can be viewed below.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 | /*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Rice University
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Rice University nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include <ompl/base/spaces/SE3StateSpace.h>
#include <ompl/geometric/SimpleSetup.h>
#include <ompl/base/goals/GoalLazySamples.h>
#include <ompl/geometric/GeneticSearch.h>
#include <ompl/config.h>
#include <iostream>
namespace ob = ompl::base;
namespace og = ompl::geometric;
/// @cond IGNORE
// describe an arbitrary representation of a goal region in SE(3)
class MyGoalRegion : public ob::GoalRegion
{
public:
MyGoalRegion(const ob::SpaceInformationPtr &si) : ob::GoalRegion(si)
{
setThreshold(1e-2);
}
virtual double distanceGoal(const ob::State *state) const
{
// goal region is given by states where x + y = z and orientation is close to identity
double d = fabs(state->as<ob::SE3StateSpace::StateType>()->getX()
+ state->as<ob::SE3StateSpace::StateType>()->getY()
- state->as<ob::SE3StateSpace::StateType>()->getZ())
+ fabs(state->as<ob::SE3StateSpace::StateType>()->rotation().w - 1.0);
return d;
}
};
// Goal regions such as the one above cannot be sampled, so
// bi-directional trees cannot be used for solving. However, we can
// transform such goal regions into ones that can be sampled. The
// caveat is that it should be possible to find states in this region
// with some other algorithm. Genetic algorithms that essentially
// perform inverse kinematics in the general sense can be used:
bool regionSamplingWithGS(const ob::SpaceInformationPtr &si, const ob::ProblemDefinitionPtr &pd, const ob::GoalRegion *region, const ob::GoalLazySamples *gls, ob::State *result)
{
og::GeneticSearch g(si);
// we can use a larger time duration for solve(), but we want to demo the ability
// of GeneticSearch to continue from where it left off
bool cont = false;
for (int i = 0 ; i < 100 ; ++i)
if (g.solve(0.05, *region, result))
{
cont = true;
break;
}
if (cont)
{
std::cout << "Found goal state: " << std::endl;
si->printState(result);
}
// we continue sampling while we are able to find solutions, we have found not more than 2 previous solutions and we have not yet solved the problem
return cont && gls->maxSampleCount() < 3 && !pd->hasSolution();
}
void planWithIK(void)
{
// construct the state space we are planning in
ob::StateSpacePtr space(new ob::SE3StateSpace());
// set the bounds for the R^3 part of SE(3)
ob::RealVectorBounds bounds(3);
bounds.setLow(-1);
bounds.setHigh(1);
space->as<ob::SE3StateSpace>()->setBounds(bounds);
// define a simple setup class
og::SimpleSetup ss(space);
// create a random start state
ob::ScopedState<ob::SE3StateSpace> start(space);
start->setXYZ(0, 0, 0);
start->rotation().setIdentity();
ss.addStartState(start);
// define our goal region
MyGoalRegion region(ss.getSpaceInformation());
// bind a sampling function that fills its argument with a sampled state and returns true while it can produce new samples
// we don't need to check if new samples are different from ones previously computed as this is pefromed automatically by GoalLazySamples
ob::GoalSamplingFn samplingFunction = boost::bind(®ionSamplingWithGS, ss.getSpaceInformation(), ss.getProblemDefinition(), ®ion, _1, _2);
// create an instance of GoalLazySamples:
ob::GoalPtr goal(new ob::GoalLazySamples(ss.getSpaceInformation(), samplingFunction));
// we set a goal that is sampleable, but it in fact corresponds to a region that is not sampleable by default
ss.setGoal(goal);
// attempt to solve the problem
ob::PlannerStatus solved = ss.solve(3.0);
if (solved)
{
std::cout << "Found solution:" << std::endl;
// print the path to screen
ss.simplifySolution();
ss.getSolutionPath().print(std::cout);
}
else
std::cout << "No solution found" << std::endl;
// the region variable will now go out of scope. To make sure it is not used in the sampling function any more
// (i.e., the sampling thread was able to terminate), we make sure sampling has terminated
goal->as<ob::GoalLazySamples>()->stopSampling();
}
/// @endcond
int main(int, char **)
{
std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
planWithIK();
return 0;
}
|