All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Types | Public Member Functions | Protected Member Functions | List of all members
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,
GeomIndexList
ObjectVec_t
 

Public Member Functions

 CollisionObject (DevicePtr_t device, const GeomIndex geom)
 Construction from global collision-object list. More...
 
 CollisionObject (GeomModelPtr_t geomModel, GeomDataPtr_t geomData, const GeomIndex geom)
 
const std::string & name () const
 
const se3::GeometryObject & pinocchio () const
 Access to pinocchio object. More...
 
se3::GeometryObject & pinocchio ()
 
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 ()
 
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 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...
 
ObjectVec_tobjectVec ()
 Get the reference to INNER|OUTER object container (marginally used). More...
 
const ObjectVec_tobjectVec () const
 

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

Constructor & Destructor Documentation

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

Construction from global collision-object list.

The joint ID is recovered from the collision object in Pinocchio and InOut is set to INNER. The geomIndexInJoint is not defined (geomIndexInJointSet = false)

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

Member Function Documentation

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

Access to fcl object.

FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( GeomData data) const
FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( ) const
FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl ( )
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.
const Transform3f& hpp::pinocchio::CollisionObject::getTransform ( ) const
const GeomIndex& hpp::pinocchio::CollisionObject::indexInModel ( ) const
inline
JointPtr_t hpp::pinocchio::CollisionObject::joint ( )

Get joint.

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

Get joint index.

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.
const std::string& hpp::pinocchio::CollisionObject::name ( ) const
ObjectVec_t& hpp::pinocchio::CollisionObject::objectVec ( )
protected

Get the reference to INNER|OUTER object container (marginally used).

const ObjectVec_t& hpp::pinocchio::CollisionObject::objectVec ( ) const
protected
const se3::GeometryObject& hpp::pinocchio::CollisionObject::pinocchio ( ) const

Access to pinocchio object.

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

Return the position in the joint frame.

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

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