DART  6.10.1
dart::collision::FCLCollisionObject Class Reference

#include <FCLCollisionObject.hpp>

Inheritance diagram for dart::collision::FCLCollisionObject:
dart::collision::CollisionObject

Public Member Functions

dart::collision::fcl::CollisionObjectgetFCLCollisionObject ()
 Return FCL collision object. More...
 
const dart::collision::fcl::CollisionObjectgetFCLCollisionObject () const
 Return FCL collision object. More...
 
CollisionDetectorgetCollisionDetector ()
 Return collision detection engine associated with this CollisionObject. More...
 
const CollisionDetectorgetCollisionDetector () const
 Return collision detection engine associated with this CollisionObject. More...
 
const dynamics::ShapeFramegetShapeFrame () const
 Return the associated ShapeFrame. More...
 
dynamics::ConstShapePtr getShape () const
 Return the associated Shape. More...
 
const Eigen::Isometry3d & getTransform () const
 Return the transformation of this CollisionObject in world coordinates. More...
 

Protected Member Functions

 FCLCollisionObject (CollisionDetector *collisionDetector, const dynamics::ShapeFrame *shapeFrame, const fcl_shared_ptr< dart::collision::fcl::CollisionGeometry > &fclCollGeom)
 Constructor. More...
 
void updateEngineData () override
 Update the collision object of the collision detection engine. More...
 

Protected Attributes

std::unique_ptr< dart::collision::fcl::CollisionObjectmFCLCollisionObject
 FCL collision object. More...
 
CollisionDetectormCollisionDetector
 Collision detector. More...
 
const dynamics::ShapeFramemShapeFrame
 ShapeFrame. More...
 

Friends

class FCLCollisionDetector
 

Constructor & Destructor Documentation

◆ FCLCollisionObject()

dart::collision::FCLCollisionObject::FCLCollisionObject ( CollisionDetector collisionDetector,
const dynamics::ShapeFrame shapeFrame,
const fcl_shared_ptr< dart::collision::fcl::CollisionGeometry > &  fclCollGeom 
)
protected

Constructor.

Member Function Documentation

◆ getCollisionDetector() [1/2]

CollisionDetector * dart::collision::CollisionObject::getCollisionDetector ( )
inherited

Return collision detection engine associated with this CollisionObject.

◆ getCollisionDetector() [2/2]

const CollisionDetector * dart::collision::CollisionObject::getCollisionDetector ( ) const
inherited

Return collision detection engine associated with this CollisionObject.

◆ getFCLCollisionObject() [1/2]

dart::collision::fcl::CollisionObject * dart::collision::FCLCollisionObject::getFCLCollisionObject ( )

Return FCL collision object.

◆ getFCLCollisionObject() [2/2]

const dart::collision::fcl::CollisionObject * dart::collision::FCLCollisionObject::getFCLCollisionObject ( ) const

Return FCL collision object.

◆ getShape()

dynamics::ConstShapePtr dart::collision::CollisionObject::getShape ( ) const
inherited

Return the associated Shape.

◆ getShapeFrame()

const dynamics::ShapeFrame * dart::collision::CollisionObject::getShapeFrame ( ) const
inherited

Return the associated ShapeFrame.

◆ getTransform()

const Eigen::Isometry3d & dart::collision::CollisionObject::getTransform ( ) const
inherited

Return the transformation of this CollisionObject in world coordinates.

◆ updateEngineData()

void dart::collision::FCLCollisionObject::updateEngineData ( )
overrideprotectedvirtual

Update the collision object of the collision detection engine.

This function will be called ahead of every collision checking by CollisionGroup.

Implements dart::collision::CollisionObject.

Friends And Related Function Documentation

◆ FCLCollisionDetector

friend class FCLCollisionDetector
friend

Member Data Documentation

◆ mCollisionDetector

CollisionDetector* dart::collision::CollisionObject::mCollisionDetector
protectedinherited

Collision detector.

◆ mFCLCollisionObject

std::unique_ptr<dart::collision::fcl::CollisionObject> dart::collision::FCLCollisionObject::mFCLCollisionObject
protected

FCL collision object.

◆ mShapeFrame

const dynamics::ShapeFrame* dart::collision::CollisionObject::mShapeFrame
protectedinherited

ShapeFrame.