![]() |
OMPL Plannification
Path planning with OMPL
|
Class for state checking for 2D and 3D planning. Extension of an abstract class used to implement the state validity checker over an octomap (using FCL ?). More...
#include <StateChecker.hpp>
Public Member Functions | |
StateChecker (const ob::SpaceInformationPtr &si) | |
Constructor. More... | |
void | loadMap (const std::string mapFile) |
Load the octomap where the states are checked. | |
void | loadMap (octomap::OcTree *octree) |
void | setCollisionMask (double x, double y, double z=0.2) |
Set the area around every state considered for state checking. | |
void | setDepthLimit (double depth_limit) |
Set the depth limit (constant for 2D checking) More... | |
virtual bool | isValid (const ob::State *state) const |
State validator. More... | |
~StateChecker () | |
Destructor. More... | |
Class for state checking for 2D and 3D planning. Extension of an abstract class used to implement the state validity checker over an octomap (using FCL ?).
Definition at line 41 of file StateChecker.hpp.
StateChecker::StateChecker | ( | const ob::SpaceInformationPtr & | si | ) |
Constructor.
Call the StateValidityChecker constructor from OMPL library and set checking dimension.
Definition at line 11 of file StateChecker.cpp.
StateChecker::~StateChecker | ( | ) |
|
virtual |
State validator.
Function that verifies if the given state is valid (i.e. is free of collision) using FCL.
Definition at line 64 of file StateChecker.cpp.
void StateChecker::setDepthLimit | ( | double | depth_limit | ) |
Set the depth limit (constant for 2D checking)
Set the lowest altitude for checking (constant depth for 2D checking). Used to prevent unwanted invalid state (Issue with the ground in Octomap)
Definition at line 59 of file StateChecker.cpp.