hpp::pinocchio::CollisionObject Class Reference

Specialization of fcl::CollisionObject to add a name to objects. More...

#include <hpp/pinocchio/collision-object.hh>

Public Types

typedef std::vector< GeomIndexGeomIndexList
 
typedef std::map< JointIndex, GeomIndexListObjectVec_t
 

Public Member Functions

 CollisionObject (DevicePtr_t device, const GeomIndex geom)
 Constructor for object of the device. More...
 
 CollisionObject (GeomModelPtr_t geomModel, GeomDataPtr_t geomData, const GeomIndex geom)
 Constructor for obstacles (object attached to the environment) It is not attached to a Device. More...
 
const std::string & name () const
 
const GeometryObjectpinocchio () const
 Access to pinocchio object. More...
 
GeometryObjectpinocchio ()
 
FclConstCollisionObjectPtr_t fcl (const GeomData &data) const
 Access to fcl object. More...
 
FclCollisionObjectPtr_t fcl (GeomData &data) const
 
FclConstCollisionObjectPtr_t fcl () const
 
FclCollisionObjectPtr_t fcl ()
 
FclCollisionObjectPtr_t fcl (DeviceData &d) const
 Returns the FCL collision object. More...
 
const JointIndexjointIndex () const
 Get joint index. More...
 
JointPtr_t joint ()
 Get joint. More...
 
JointConstPtr_t joint () const
 
const Transform3fpositionInJointFrame () const
 Return the position in the joint frame. More...
 
const fcl::Transform3f & getFclTransform () const
 Return transform of the fcl object. More...
 
const Transform3fgetTransform () const
 
const Transform3fgetTransform (DeviceData &d) const
 
const GeomIndexindexInModel () const
 
void move (const Transform3f &position)
 Move object to given position. More...
 

Protected Member Functions

void selfAssert () const
 Assert that the members of the struct are valid (no null pointer, etc). More...
 

Detailed Description

Specialization of fcl::CollisionObject to add a name to objects.

Objects moved by a robot joint. They can collide each other and distance computation can be computed between them.

Member Typedef Documentation

◆ GeomIndexList

◆ ObjectVec_t

Constructor & Destructor Documentation

◆ CollisionObject() [1/2]

hpp::pinocchio::CollisionObject::CollisionObject ( DevicePtr_t  device,
const GeomIndex  geom 
)

Constructor for object of the device.

◆ CollisionObject() [2/2]

hpp::pinocchio::CollisionObject::CollisionObject ( GeomModelPtr_t  geomModel,
GeomDataPtr_t  geomData,
const GeomIndex  geom 
)

Constructor for obstacles (object attached to the environment) It is not attached to a Device.

Member Function Documentation

◆ fcl() [1/5]

FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( const GeomData data) const

Access to fcl object.

◆ fcl() [2/5]

FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( GeomData data) const

◆ fcl() [3/5]

FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( ) const

◆ fcl() [4/5]

FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( )

◆ fcl() [5/5]

FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( DeviceData d) const

Returns the FCL collision object.

Parameters
dIgnored if this object represents an obstacle. Otherwise, a DeviceData for the internal device.

◆ getFclTransform()

const fcl::Transform3f& hpp::pinocchio::CollisionObject::getFclTransform ( ) const

Return transform of the fcl object.

Warning
If joint linked object -as a robot body- and the robot is manually moved, this will return the non-update transform.
Note
If object is not attached to a joint, use move() to update transform between hpp and fcl.

◆ getTransform() [1/2]

const Transform3f& hpp::pinocchio::CollisionObject::getTransform ( ) const

◆ getTransform() [2/2]

const Transform3f& hpp::pinocchio::CollisionObject::getTransform ( DeviceData d) const

◆ indexInModel()

const GeomIndex& hpp::pinocchio::CollisionObject::indexInModel ( ) const
inline

◆ joint() [1/2]

JointPtr_t hpp::pinocchio::CollisionObject::joint ( )

Get joint.

◆ joint() [2/2]

JointConstPtr_t hpp::pinocchio::CollisionObject::joint ( ) const

◆ jointIndex()

const JointIndex& hpp::pinocchio::CollisionObject::jointIndex ( ) const
inline

Get joint index.

◆ move()

void hpp::pinocchio::CollisionObject::move ( const Transform3f position)

Move object to given position.

Note
This method should only be executed on objects not attached to a robot body (ie attached to the "universe", joint 0). This statement is asserted.

◆ name()

const std::string& hpp::pinocchio::CollisionObject::name ( ) const

◆ pinocchio() [1/2]

const GeometryObject& hpp::pinocchio::CollisionObject::pinocchio ( ) const

Access to pinocchio object.

◆ pinocchio() [2/2]

GeometryObject& hpp::pinocchio::CollisionObject::pinocchio ( )

◆ positionInJointFrame()

const Transform3f& hpp::pinocchio::CollisionObject::positionInJointFrame ( ) const

Return the position in the joint frame.

◆ selfAssert()

void hpp::pinocchio::CollisionObject::selfAssert ( ) const
protected

Assert that the members of the struct are valid (no null pointer, etc).