Program Listing for File PathHybridization.h
↰ Return to documentation for file (src/ompl/geometric/PathHybridization.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2011, Willow Garage, Inc.
* 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 Willow Garage 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 */
#ifndef OMPL_GEOMETRIC_PATH_HYBRIDIZATION_
#define OMPL_GEOMETRIC_PATH_HYBRIDIZATION_
#include "ompl/base/SpaceInformation.h"
#include "ompl/base/OptimizationObjective.h"
#include "ompl/geometric/PathGeometric.h"
#include <boost/graph/graph_traits.hpp>
#include <boost/graph/adjacency_list.hpp>
#include <iostream>
#include <set>
namespace ompl
{
namespace geometric
{
OMPL_CLASS_FORWARD(PathHybridization);
class PathHybridization
{
public:
PathHybridization(base::SpaceInformationPtr si);
PathHybridization(base::SpaceInformationPtr si, base::OptimizationObjectivePtr obj);
~PathHybridization();
const geometric::PathGeometricPtr &getHybridPath() const;
void computeHybridPath();
unsigned int recordPath(const geometric::PathGeometricPtr &pp, bool matchAcrossGaps);
std::size_t pathCount() const;
void matchPaths(const geometric::PathGeometric &p, const geometric::PathGeometric &q, double gapValue,
std::vector<int> &indexP, std::vector<int> &indexQ) const;
void clear();
void print(std::ostream &out = std::cout) const;
const std::string &getName() const;
private:
struct vertex_state_t
{
using kind = boost::vertex_property_tag;
};
using HGraph = boost::adjacency_list<
boost::vecS, boost::vecS, boost::undirectedS,
boost::property<vertex_state_t, base::State *,
boost::property<boost::vertex_predecessor_t, unsigned long int,
boost::property<boost::vertex_rank_t, base::Cost>>>,
boost::property<boost::edge_weight_t, base::Cost>>;
using Vertex = boost::graph_traits<HGraph>::vertex_descriptor;
using Edge = boost::graph_traits<HGraph>::edge_descriptor;
struct PathInfo
{
PathInfo(const geometric::PathGeometricPtr &path)
: path_(path), states_(path->getStates()), cost_(base::Cost())
{
vertices_.reserve(states_.size());
}
bool operator==(const PathInfo &other) const
{
return path_ == other.path_;
}
bool operator<(const PathInfo &other) const
{
return path_ < other.path_;
}
geometric::PathGeometricPtr path_;
const std::vector<base::State *> &states_;
base::Cost cost_;
std::vector<Vertex> vertices_;
};
void attemptNewEdge(const PathInfo &p, const PathInfo &q, int indexP, int indexQ);
base::SpaceInformationPtr si_;
base::OptimizationObjectivePtr obj_;
HGraph g_;
boost::property_map<HGraph, vertex_state_t>::type stateProperty_;
Vertex root_;
Vertex goal_;
std::set<PathInfo> paths_;
geometric::PathGeometricPtr hpath_;
std::string name_;
};
}
}
#endif