#include <multibody/geometry.hpp>
Public Types | |
typedef Model::Index | Index |
typedef Model::JointIndex | JointIndex |
typedef Model::GeomIndex | GeomIndex |
typedef std::list< GeomIndex > | GeomIndexList |
Public Member Functions | |
GeometryModel (const se3::Model &model) | |
~GeometryModel () | |
GeomIndex | addCollisionObject (const JointIndex parent, const fcl::CollisionObject &co, const SE3 &placement, const std::string &geom_name="", const std::string &mesh_path="") |
Add a geometry object whose type is COLLISION to a GeometryModel. | |
GeomIndex | addVisualObject (const JointIndex parent, const fcl::CollisionObject &co, const SE3 &placement, const std::string &geom_name="", const std::string &mesh_path="") |
Add a geometry object whose type is VISUAL to a GeometryModel. | |
GeomIndex | getCollisionId (const std::string &name) const |
Return the index of a GeometryObject of type COLLISION given by its name. | |
GeomIndex | getVisualId (const std::string &name) const |
Return the index of a GeometryObject of type VISUAL given by its name. | |
bool | existCollisionName (const std::string &name) const |
Check if a GeometryObject of type COLLISION given by its name exists. | |
bool | existVisualName (const std::string &name) const |
Check if a GeometryObject of type VISUAL given by its name exists. | |
const std::string & | getCollisionName (const GeomIndex index) const |
Get the name of a GeometryObject of type COLLISION given by its index. | |
const std::string & | getVisualName (const GeomIndex index) const |
Get the name of a GeometryObject of type VISUAL given by its index. | |
void | addInnerObject (const JointIndex joint, const GeomIndex inner_object) |
Associate a GeometryObject of type COLLISION to a joint's inner objects list. | |
void | addOutterObject (const JointIndex joint, const GeomIndex outer_object) |
Associate a GeometryObject of type COLLISION to a joint's outer objects list. | |
Public Attributes | |
const se3::Model & | model |
A const reference to the reference model. | |
Index | ncollisions |
The number of GeometryObjects that are of type COLLISION. | |
Index | nvisuals |
The number of GeometryObjects that are of type visuals. | |
std::vector< GeometryObject > | collision_objects |
Vector of GeometryObjects used for collision computations. | |
std::vector< GeometryObject > | visual_objects |
Vector of GeometryObjects used for visualisation. | |
std::map< JointIndex, GeomIndexList > | innerObjects |
A list of associated collision GeometryObjects to a given joint Id. | |
std::map< JointIndex, GeomIndexList > | outerObjects |
A list of associated collision GeometryObjects to a given joint Id Outer objects can be seen as geometry objects that may often be obstacles to the Inner objects of given joint. | |
Friends | |
std::ostream & | operator<< (std::ostream &os, const GeometryModel &model_geom) |
typedef std::list<GeomIndex> se3::GeometryModel::GeomIndexList |
se3::GeometryModel::GeometryModel | ( | const se3::Model & | model | ) | [inline] |
se3::GeometryModel::~GeometryModel | ( | ) | [inline] |
GeomIndex se3::GeometryModel::addCollisionObject | ( | const JointIndex | parent, |
const fcl::CollisionObject & | co, | ||
const SE3 & | placement, | ||
const std::string & | geom_name = "" , |
||
const std::string & | mesh_path = "" |
||
) |
Add a geometry object whose type is COLLISION to a GeometryModel.
[in] | parent | Index of the parent joint |
[in] | co | The actual fcl CollisionObject |
[in] | placement | The relative placement regarding to the parent frame |
[in] | geom_name | The name of the Geometry Object |
[in] | mesh_path | The absolute path to the mesh |
void se3::GeometryModel::addInnerObject | ( | const JointIndex | joint, |
const GeomIndex | inner_object | ||
) |
Associate a GeometryObject of type COLLISION to a joint's inner objects list.
[in] | joint | Index of the joint |
[in] | inner_object | Index of the GeometryObject that will be an inner object |
void se3::GeometryModel::addOutterObject | ( | const JointIndex | joint, |
const GeomIndex | outer_object | ||
) |
Associate a GeometryObject of type COLLISION to a joint's outer objects list.
[in] | joint | Index of the joint |
[in] | inner_object | Index of the GeometryObject that will be an outer object |
GeomIndex se3::GeometryModel::addVisualObject | ( | const JointIndex | parent, |
const fcl::CollisionObject & | co, | ||
const SE3 & | placement, | ||
const std::string & | geom_name = "" , |
||
const std::string & | mesh_path = "" |
||
) |
Add a geometry object whose type is VISUAL to a GeometryModel.
[in] | parent | Index of the parent joint |
[in] | co | The actual fcl CollisionObject |
[in] | placement | The relative placement regarding to the parent frame |
[in] | geom_name | The name of the Geometry Object |
[in] | mesh_path | The absolute path to the mesh |
bool se3::GeometryModel::existCollisionName | ( | const std::string & | name | ) | const |
Check if a GeometryObject of type COLLISION given by its name exists.
[in] | name | Name of the GeometryObject |
bool se3::GeometryModel::existVisualName | ( | const std::string & | name | ) | const |
Check if a GeometryObject of type VISUAL given by its name exists.
[in] | name | Name of the GeometryObject |
GeomIndex se3::GeometryModel::getCollisionId | ( | const std::string & | name | ) | const |
Return the index of a GeometryObject of type COLLISION given by its name.
[in] | name | Name of the GeometryObject |
const std::string& se3::GeometryModel::getCollisionName | ( | const GeomIndex | index | ) | const |
Get the name of a GeometryObject of type COLLISION given by its index.
[in] | index | Index of the GeometryObject |
GeomIndex se3::GeometryModel::getVisualId | ( | const std::string & | name | ) | const |
Return the index of a GeometryObject of type VISUAL given by its name.
[in] | name | Name of the GeometryObject |
const std::string& se3::GeometryModel::getVisualName | ( | const GeomIndex | index | ) | const |
Get the name of a GeometryObject of type VISUAL given by its index.
[in] | index | Index of the GeometryObject |
std::ostream& operator<< | ( | std::ostream & | os, |
const GeometryModel & | model_geom | ||
) | [friend] |
std::vector<GeometryObject> se3::GeometryModel::collision_objects |
Vector of GeometryObjects used for collision computations.
Referenced by se3::updateGeometryPlacements().
std::map< JointIndex, GeomIndexList > se3::GeometryModel::innerObjects |
A list of associated collision GeometryObjects to a given joint Id.
Inner objects can be seen as geometry objects that directly move when the associated joint moves
A const reference to the reference model.
The number of GeometryObjects that are of type COLLISION.
Referenced by se3::GeometryData::GeometryData(), and se3::updateGeometryPlacements().
The number of GeometryObjects that are of type visuals.
Referenced by se3::updateGeometryPlacements().
std::map< JointIndex, GeomIndexList > se3::GeometryModel::outerObjects |
A list of associated collision GeometryObjects to a given joint Id Outer objects can be seen as geometry objects that may often be obstacles to the Inner objects of given joint.
std::vector<GeometryObject> se3::GeometryModel::visual_objects |
Vector of GeometryObjects used for visualisation.
Referenced by se3::updateGeometryPlacements().