31 #ifndef HPP_PINOCCHIO_COLLISION_OBJECT_HH
32 #define HPP_PINOCCHIO_COLLISION_OBJECT_HH
38 #include <pinocchio/multibody/fwd.hpp>
65 const std::string&
name()
const;
Definition: collision-object.hh:52
CollisionObject(DevicePtr_t device, const GeomIndex geom)
Constructor for object of the device.
const std::string & name() const
const GeometryObject & pinocchio() const
Access to pinocchio object.
FclCollisionObjectPtr_t fcl(DeviceData &d) const
FclConstCollisionObjectPtr_t fcl(const DeviceData &d) const
void selfAssert() const
Assert that the members of the struct are valid (no null pointer, etc).
CollisionObject(GeomModelPtr_t geomModel, GeomDataPtr_t geomData, const GeomIndex geom)
JointPtr_t joint()
Get joint.
std::map< JointIndex, GeomIndexList > ObjectVec_t
Definition: collision-object.hh:55
JointConstPtr_t joint() const
const Transform3f & getTransform(const DeviceData &d) const
FclConstCollisionObjectPtr_t fcl(const GeomData &data) const
Access to fcl object.
FclCollisionObjectPtr_t fcl(GeomData &data) const
CollisionGeometryPtr_t geometry() const
Access to fcl object.
const GeomIndex & indexInModel() const
Definition: collision-object.hh:105
fcl::Transform3f getFclTransform() const
const JointIndex & jointIndex() const
Get joint index.
Definition: collision-object.hh:87
FclConstCollisionObjectPtr_t fcl() const
FclCollisionObjectPtr_t fcl()
void move(const Transform3f &position)
GeometryObject & pinocchio()
const Transform3f & getTransform() const
std::vector< GeomIndex > GeomIndexList
Definition: collision-object.hh:54
const Transform3f & positionInJointFrame() const
Return the position in the joint frame.
#define HPP_PINOCCHIO_DLLAPI
Definition: config.hh:64
shared_ptr< Device > DevicePtr_t
Definition: fwd.hh:118
shared_ptr< Joint > JointPtr_t
Definition: fwd.hh:123
shared_ptr< GeomModel > GeomModelPtr_t
Definition: fwd.hh:133
::pinocchio::GeometryData GeomData
Definition: fwd.hh:79
::pinocchio::GeometryObject GeometryObject
Definition: collision-object.hh:46
shared_ptr< GeomData > GeomDataPtr_t
Definition: fwd.hh:135
::pinocchio::GeomIndex GeomIndex
Definition: fwd.hh:75
::pinocchio::SE3 Transform3f
Definition: fwd.hh:80
fcl::CollisionObject * FclCollisionObjectPtr_t
Definition: fwd.hh:114
::pinocchio::JointIndex JointIndex
Definition: fwd.hh:73
shared_ptr< const Joint > JointConstPtr_t
Definition: fwd.hh:124
const fcl::CollisionObject * FclConstCollisionObjectPtr_t
Definition: fwd.hh:115
Utility functions.
Definition: body.hh:39
Definition: collision-object.hh:40
Definition: device-data.hh:51