ompl::app::RigidBodyGeometry Class Reference
Inheritance diagram for ompl::app::RigidBodyGeometry:
Public Member Functions | |
RigidBodyGeometry (MotionModel mtype, CollisionChecker ctype) | |
Constructor expects a state space that can represent a rigid body. More... | |
RigidBodyGeometry (MotionModel mtype) | |
Constructor expects a state space that can represent a rigid body. More... | |
MotionModel | getMotionModel () const |
CollisionChecker | getCollisionCheckerType () const |
bool | hasEnvironment () const |
bool | hasRobot () const |
unsigned int | getLoadedRobotCount () const |
aiVector3D | getRobotCenter (unsigned int robotIndex) const |
Get the robot's center (average of all the vertices of all its parts) | |
virtual bool | setEnvironmentMesh (const std::string &env) |
This function specifies the name of the CAD file representing the environment (env). Returns 1 on success, 0 on failure. | |
virtual bool | addEnvironmentMesh (const std::string &env) |
This function specifies the name of the CAD file representing a part of the environment (env). Returns 1 on success, 0 on failure. | |
virtual bool | setRobotMesh (const std::string &robot) |
This function specifies the name of the CAD file representing the robot (robot). Returns 1 on success, 0 on failure. | |
virtual bool | addRobotMesh (const std::string &robot) |
This function specifies the name of the CAD file representing a part of the robot (robot). Returns 1 on success, 0 on failure. | |
virtual void | setStateValidityCheckerType (CollisionChecker ctype) |
Change the type of collision checking for the rigid body. | |
const base::StateValidityCheckerPtr & | allocStateValidityChecker (const base::SpaceInformationPtr &si, const GeometricStateExtractor &se, bool selfCollision) |
Allocate default state validity checker using FCL. | |
const GeometrySpecification & | getGeometrySpecification () const |
void | setBoundsFactor (double factor) |
The bounds of the environment are inferred based on the axis-aligned bounding box for the objects in the environment. The inferred size is multiplied by factor. By default factor = 1,. | |
double | getBoundsFactor () const |
Get the data set by setBoundsFactor() | |
void | setBoundsAddition (double add) |
The bounds of the environment are inferred based on the axis-aligned bounding box for the objects in the environment. add is added to the inferred size. By default add = 0,. | |
double | getBoundsAddition () const |
Get the data set by setBoundsAddition() | |
base::RealVectorBounds | inferEnvironmentBounds () const |
Given the representation of an environment, infer its bounds. The bounds will be 2-dimensional when planning in 2D and 3-dimensional when planning in 3D. | |
void | setMeshPath (const std::vector< boost::filesystem::path > &path) |
set path to search for mesh files | |
Protected Member Functions | |
boost::filesystem::path | findMeshFile (const std::string &fname) |
return absolute path to mesh file if it exists and an empty path otherwise | |
void | computeGeometrySpecification () |
Protected Attributes | |
MotionModel | mtype_ |
double | factor_ |
The factor to multiply inferred environment bounds by (default 1) | |
double | add_ |
The value to add to inferred environment bounds (default 0) | |
std::vector< std::shared_ptr< Assimp::Importer > > | importerEnv_ |
Instance of assimp importer used to load environment. | |
std::vector< std::shared_ptr< Assimp::Importer > > | importerRobot_ |
Instance of assimp importer used to load robot. | |
GeometrySpecification | geom_ |
Object containing mesh data for robot and environment. | |
base::StateValidityCheckerPtr | validitySvc_ |
Instance of the state validity checker for collision checking. | |
CollisionChecker | ctype_ |
Value containing the type of collision checking to use. | |
std::vector< boost::filesystem::path > | meshPath_ {OMPLAPP_RESOURCE_DIR} |
Paths to search for mesh files if mesh file names do not correspond to absolute paths. | |
Detailed Description
Definition at line 53 of file RigidBodyGeometry.h.
Constructor & Destructor Documentation
◆ RigidBodyGeometry() [1/2]
|
inlineexplicit |
Constructor expects a state space that can represent a rigid body.
- Parameters
-
mtype The motion model (2D or 3D) for the rigid body. ctype The type of collision checker to use for rigid body planning.
Definition at line 61 of file RigidBodyGeometry.h.
◆ RigidBodyGeometry() [2/2]
|
inlineexplicit |
Constructor expects a state space that can represent a rigid body.
- Parameters
-
mtype The motion model (2D or 3D) for the rigid body.
- Remarks
- This constructor defaults to a PQP state validity checker
Definition at line 69 of file RigidBodyGeometry.h.
The documentation for this class was generated from the following files:
- omplapp/geometry/RigidBodyGeometry.h
- omplapp/geometry/RigidBodyGeometry.cpp