se3::GeometryObject Struct Reference

#include <multibody/geometry.hpp>

Collaboration diagram for se3::GeometryObject:
[legend]

List of all members.

Public Types

typedef Model::Index Index
typedef Model::JointIndex JointIndex
typedef Model::GeomIndex GeomIndex

Public Member Functions

 GeometryObject (const GeometryType type, const std::string &name, const JointIndex parent, const fcl::CollisionObject &collision, const SE3 &placement, const std::string &mesh_path)
GeometryObjectoperator= (const GeometryObject &other)

Public Attributes

GeometryType type
 Type of the GeometryObject. Cann be VISUAL, COLLISION, or NONE (cf GeometryType enumeration)
std::string name
 Name of the geometry object.
JointIndex parent
 Index of the parent joint.
fcl::CollisionObject collision_object
 The actual cloud of points representing the collision mesh of the object.
SE3 placement
 Position of geometry object in parent joint's frame.
std::string mesh_path
 Absolute path to the mesh file.

Member Typedef Documentation


Constructor & Destructor Documentation

se3::GeometryObject::GeometryObject ( const GeometryType  type,
const std::string &  name,
const JointIndex  parent,
const fcl::CollisionObject &  collision,
const SE3 placement,
const std::string &  mesh_path 
) [inline]

Member Function Documentation

GeometryObject& se3::GeometryObject::operator= ( const GeometryObject other) [inline]

Member Data Documentation

The actual cloud of points representing the collision mesh of the object.

Referenced by operator=(), and se3::operator==().

Position of geometry object in parent joint's frame.

Referenced by se3::operator<<(), operator=(), and se3::operator==().

Type of the GeometryObject. Cann be VISUAL, COLLISION, or NONE (cf GeometryType enumeration)

Referenced by se3::operator<<(), operator=(), and se3::operator==().