Public Member Functions |
Protected Types |
Protected Member Functions |
Protected Attributes |
List of all members
ompl::app::PQPStateValidityChecker< T > Class Template Reference
Define an ompl::base::StateValidityChecker that can construct PQP models internally. The instance is still abstract however, as the isValid() function is not implemented (knowledge of the state space is needed for this function to be implemented) More...
#include <omplapp/geometry/detail/PQPStateValidityChecker.h>
Inheritance diagram for ompl::app::PQPStateValidityChecker< T >:
Public Member Functions | |
PQPStateValidityChecker (const base::SpaceInformationPtr &si, const GeometrySpecification &geom, GeometricStateExtractor se, bool selfCollision) | |
bool | isValid (const base::State *state) const override |
Return true if the state state is valid. Usually, this means at least collision checking. If it is possible that ompl::base::StateSpace::interpolate() or ompl::control::ControlSpace::propagate() return states that are outside of bounds, this function should also make a call to ompl::base::SpaceInformation::satisfiesBounds(). | |
double | clearance (const base::State *state) const override |
Report the distance to the nearest invalid state when starting from state. If the distance is negative, the value of clearance is the penetration depth. | |
Public Member Functions inherited from ompl::base::StateValidityChecker | |
StateValidityChecker (SpaceInformation *si) | |
Constructor. | |
StateValidityChecker (const SpaceInformationPtr &si) | |
Constructor. | |
virtual bool | isValid (const State *state, double &dist) const |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state. | |
virtual bool | isValid (const State *state, double &dist, State *validState, bool &validStateAvailable) const |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state (using clearance()). If a direction that moves state away from being invalid is available, a valid state in that direction is also set (validState). validStateAvailable is set to true if validState is updated. | |
virtual double | clearance (const State *state, State *, bool &validStateAvailable) const |
Report the distance to the nearest invalid state when starting from state, and if possible, also specify a valid state validState in the direction that moves away from the colliding state. The validStateAvailable flag is set to true if validState is updated. | |
const StateValidityCheckerSpecs & | getSpecs () const |
Return the specifications (capabilities of this state validity checker) | |
virtual bool | operator== (const StateValidityChecker &) const |
Checks for equivalence between two Statevaliditycheckers. | |
bool | operator!= (const StateValidityChecker &rhs) const |
Protected Types | |
using | PQPModelPtr = std::shared_ptr< PQP_Model > |
Shared pointer wrapper for PQP_Model. | |
Protected Member Functions | |
void | configure (const GeometrySpecification &geom) |
std::pair< PQPModelPtr, double > | getPQPModelFromScene (const aiScene *scene, const aiVector3D ¢er) const |
std::pair< PQPModelPtr, double > | getPQPModelFromScene (const std::vector< const aiScene * > &scenes, const std::vector< aiVector3D > ¢er) const |
Convert a mesh to a PQP model. | |
std::pair< PQPModelPtr, double > | getPQPModelFromTris (const std::vector< aiVector3D > &triangles) const |
Convert a set of triangles to a PQP model, but add extra padding if a particular dimension is disproportionately small. | |
Protected Attributes | |
OMPL_StateType< T > | stateConvertor_ |
GeometricStateExtractor | extractState_ |
bool | selfCollision_ |
std::vector< PQPModelPtr > | robotParts_ |
Model of the robot. | |
PQPModelPtr | environment_ |
Model of the environment. | |
double | avgEnvSide_ |
The average length of a side in the environment. | |
double | distanceTol_ |
Tolerance passed to PQP for distance calculations. | |
std::mutex | mutex_ |
Protected Attributes inherited from ompl::base::StateValidityChecker | |
SpaceInformation * | si_ |
The instance of space information this state validity checker operates on. | |
StateValidityCheckerSpecs | specs_ |
The specifications of the state validity checker (its capabilities) | |
Detailed Description
template<MotionModel T>
class ompl::app::PQPStateValidityChecker< T >
Define an ompl::base::StateValidityChecker that can construct PQP models internally. The instance is still abstract however, as the isValid() function is not implemented (knowledge of the state space is needed for this function to be implemented)
Definition at line 132 of file PQPStateValidityChecker.h.
The documentation for this class was generated from the following file:
- omplapp/geometry/detail/PQPStateValidityChecker.h