| hpp-pinocchio 6.0.0
    Wrapping of the kinematic/dynamic chain Pinocchio for HPP. | 
#include <hpp/pinocchio/collision-object.hh>
| Public Types | |
| typedef std::vector< GeomIndex > | GeomIndexList | 
| typedef std::map< JointIndex, GeomIndexList > | ObjectVec_t | 
| Public Member Functions | |
| CollisionObject (DevicePtr_t device, const GeomIndex geom) | |
| Constructor for object of the device. | |
| CollisionObject (GeomModelPtr_t geomModel, GeomDataPtr_t geomData, const GeomIndex geom) | |
| const std::string & | name () const | 
| const GeometryObject & | pinocchio () const | 
| Access to pinocchio object. | |
| GeometryObject & | pinocchio () | 
| CollisionGeometryPtr_t | geometry () const | 
| Access to coal object. | |
| FclConstCollisionObjectPtr_t | fcl (const GeomData &data) const | 
| Access to coal object. | |
| FclCollisionObjectPtr_t | fcl (GeomData &data) const | 
| FclConstCollisionObjectPtr_t | fcl () const | 
| FclCollisionObjectPtr_t | fcl () | 
| FclCollisionObjectPtr_t | fcl (DeviceData &d) const | 
| FclConstCollisionObjectPtr_t | fcl (const DeviceData &d) const | 
| const JointIndex & | jointIndex () const | 
| Get joint index. | |
| JointPtr_t | joint () | 
| Get joint. | |
| JointConstPtr_t | joint () const | 
| const Transform3s & | positionInJointFrame () const | 
| Return the position in the joint frame. | |
| coal::Transform3s | getFclTransform () const | 
| const Transform3s & | getTransform () const | 
| const Transform3s & | getTransform (const DeviceData &d) const | 
| const GeomIndex & | indexInModel () const | 
| void | move (const Transform3s &position) | 
| Protected Member Functions | |
| void | selfAssert () const | 
| Assert that the members of the struct are valid (no null pointer, etc). | |
Specialization of coal::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.
| typedef std::vector<GeomIndex> hpp::pinocchio::CollisionObject::GeomIndexList | 
| typedef std::map<JointIndex, GeomIndexList> hpp::pinocchio::CollisionObject::ObjectVec_t | 
| hpp::pinocchio::CollisionObject::CollisionObject | ( | DevicePtr_t | device, | 
| const GeomIndex | geom | ||
| ) | 
Constructor for object of the device.
| 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.
| FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | ) | 
| FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | ) | const | 
| FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | const DeviceData & | d | ) | const | 
| FclConstCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | const GeomData & | data | ) | const | 
Access to coal object.
| FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | DeviceData & | d | ) | const | 
Returns the FCL collision object.
| d | Ignored if this object represents an obstacle. Otherwise, a DeviceData for the internal device. | 
| FclCollisionObjectPtr_t hpp::pinocchio::CollisionObject::fcl | ( | GeomData & | data | ) | const | 
| CollisionGeometryPtr_t hpp::pinocchio::CollisionObject::geometry | ( | ) | const | 
Access to coal object.
| coal::Transform3s hpp::pinocchio::CollisionObject::getFclTransform | ( | ) | const | 
Return transform of the coal object
| const Transform3s & hpp::pinocchio::CollisionObject::getTransform | ( | ) | const | 
| const Transform3s & hpp::pinocchio::CollisionObject::getTransform | ( | const DeviceData & | d | ) | const | 
| 
 | inline | 
| JointPtr_t hpp::pinocchio::CollisionObject::joint | ( | ) | 
Get joint.
| JointConstPtr_t hpp::pinocchio::CollisionObject::joint | ( | ) | const | 
| 
 | inline | 
Get joint index.
| void hpp::pinocchio::CollisionObject::move | ( | const Transform3s & | position | ) | 
Move object to given position
| const std::string & hpp::pinocchio::CollisionObject::name | ( | ) | const | 
| GeometryObject & hpp::pinocchio::CollisionObject::pinocchio | ( | ) | 
| const GeometryObject & hpp::pinocchio::CollisionObject::pinocchio | ( | ) | const | 
Access to pinocchio object.
| const Transform3s & hpp::pinocchio::CollisionObject::positionInJointFrame | ( | ) | const | 
Return the position in the joint frame.
| 
 | protected | 
Assert that the members of the struct are valid (no null pointer, etc).