#include <ColdetModel.h>
Public Types | |
enum | PrimitiveType { SP_MESH, SP_BOX, SP_CYLINDER, SP_CONE, SP_SPHERE, SP_PLANE } |
Public Member Functions | |
void | addTriangle (int v1, int v2, int v3) |
void | addVertex (float x, float y, float z) |
void | build () |
build tree of bounding boxes to accelerate collision check More... | |
bool | checkCollisionWithPointCloud (const std::vector< Vector3 > &i_cloud, double i_radius) |
check collision between this triangle mesh and a point cloud More... | |
ColdetModel () | |
constructor More... | |
ColdetModel (const ColdetModel &org) | |
copy constructor More... | |
double | computeDistanceWithRay (const double *point, const double *dir) |
compute distance between a point and this mesh along ray More... | |
int | getAABBmaxNum () |
int | getAABBTreeDepth () |
void | getBoundingBoxData (const int depth, std::vector< Vector3 > &out_boxes) |
ColdetModelSharedDataSet * | getDataSet () |
int | getNumTriangles () const |
int | getNumVertices () const |
get the number of vertices More... | |
bool | getPrimitiveParam (unsigned int index, float &value) const |
get a parameter of primitive More... | |
PrimitiveType | getPrimitiveType () const |
get primitive type More... | |
void | getTriangle (int index, int &out_v1, int &out_v2, int &out_v3) const |
void | getVertex (int index, float &out_x, float &out_y, float &out_z) const |
get a vertex More... | |
bool | isValid () const |
check if build() is already called or not More... | |
const std::string & | name () const |
get name of this model More... | |
int | numofBBtoDepth (int minNumofBB) |
void | setName (const std::string &name) |
set name of this model More... | |
void | setNumPrimitiveParams (unsigned int nparam) |
set the number of parameters of primitive More... | |
void | setNumTriangles (int n) |
set the number of triangles More... | |
void | setNumVertices (int n) |
set the number of vertices More... | |
void | setPosition (const Matrix33 &R, const Vector3 &p) |
set position and orientation of this model More... | |
void | setPosition (const double *R, const double *p) |
set position and orientation of this model More... | |
bool | setPrimitiveParam (unsigned int index, float value) |
set a parameter of primitive More... | |
void | setPrimitivePosition (const double *R, const double *p) |
set position and orientation of primitive More... | |
void | setPrimitiveType (PrimitiveType ptype) |
set primitive type More... | |
void | setTriangle (int index, int v1, int v2, int v3) |
add a triangle More... | |
void | setVertex (int index, float x, float y, float z) |
add a vertex More... | |
virtual | ~ColdetModel () |
destructor More... | |
Public Member Functions inherited from hrp::Referenced | |
Referenced () | |
virtual | ~Referenced () |
Private Member Functions | |
void | initialize () |
common part of constuctors More... | |
void | initNeighbor (int n) |
void | setNeighbor (int triangle0, int triangle1) |
void | setNeighborTriangle (int triangle, int vertex0, int vertex1, int vertex2) |
bool | setNeighborTriangleSub (int triangle, int vertex0, int vertex1) |
Private Attributes | |
ColdetModelSharedDataSet * | dataSet |
bool | isValid_ |
std::string | name_ |
IceMaths::Matrix4x4 * | pTransform |
transform of primitive More... | |
IceMaths::Matrix4x4 * | transform |
EdgeToTriangleMap | triangleMap |
Friends | |
class | ColdetModelPair |
Additional Inherited Members | |
Protected Member Functions inherited from hrp::Referenced | |
int | refCounter () |
Definition at line 61 of file ColdetModel.h.
Enumerator | |
---|---|
SP_MESH | |
SP_BOX | |
SP_CYLINDER | |
SP_CONE | |
SP_SPHERE | |
SP_PLANE |
Definition at line 64 of file ColdetModel.h.
ColdetModel::ColdetModel | ( | ) |
constructor
Definition at line 24 of file ColdetModel.cpp.
ColdetModel::ColdetModel | ( | const ColdetModel & | org | ) |
copy constructor
Shape information stored in dataSet is shared with org
Definition at line 34 of file ColdetModel.cpp.
|
virtual |
destructor
Definition at line 63 of file ColdetModel.cpp.
add a triangle to the end of the vector
Definition at line 137 of file ColdetModel.cpp.
void ColdetModel::addVertex | ( | float | x, |
float | y, | ||
float | z | ||
) |
add a vertex to the end of the vector
Definition at line 104 of file ColdetModel.cpp.
void ColdetModel::build | ( | ) |
build tree of bounding boxes to accelerate collision check
This method must be called before doing collision check
Definition at line 143 of file ColdetModel.cpp.
bool ColdetModel::checkCollisionWithPointCloud | ( | const std::vector< Vector3 > & | i_cloud, |
double | i_radius | ||
) |
check collision between this triangle mesh and a point cloud
i_cloud | points |
i_radius | radius of spheres assigned to the points |
Definition at line 331 of file ColdetModel.cpp.
compute distance between a point and this mesh along ray
point | a point |
dir | direction of ray |
Definition at line 314 of file ColdetModel.cpp.
int ColdetModel::getAABBmaxNum | ( | ) |
Definition at line 201 of file ColdetModel.cpp.
int ColdetModel::getAABBTreeDepth | ( | ) |
Definition at line 197 of file ColdetModel.cpp.
Definition at line 223 of file ColdetModel.cpp.
|
inline |
Definition at line 245 of file ColdetModel.h.
int ColdetModel::getNumTriangles | ( | ) | const |
Definition at line 92 of file ColdetModel.cpp.
int ColdetModel::getNumVertices | ( | ) | const |
get the number of vertices
Definition at line 79 of file ColdetModel.cpp.
bool ColdetModel::getPrimitiveParam | ( | unsigned int | index, |
float & | value | ||
) | const |
get a parameter of primitive
index | index of the parameter |
value | value of the parameter |
Definition at line 298 of file ColdetModel.cpp.
ColdetModel::PrimitiveType ColdetModel::getPrimitiveType | ( | ) | const |
Definition at line 128 of file ColdetModel.cpp.
get a vertex
index | index of the vertex |
out_x | x position of the vertex |
out_y | y position of the vertex |
out_z | z position of the vertex |
Definition at line 110 of file ColdetModel.cpp.
|
private |
common part of constuctors
Definition at line 43 of file ColdetModel.cpp.
Definition at line 383 of file ColdetModel.cpp.
|
inline |
check if build() is already called or not
Definition at line 165 of file ColdetModel.h.
|
inline |
Definition at line 190 of file ColdetModel.cpp.
set name of this model
name | name of this model |
Definition at line 87 of file ColdetModel.h.
Definition at line 387 of file ColdetModel.cpp.
|
private |
Definition at line 351 of file ColdetModel.cpp.
Definition at line 357 of file ColdetModel.cpp.
set the number of parameters of primitive
nparam | the number of parameters of primitive |
Definition at line 285 of file ColdetModel.cpp.
set the number of triangles
n | the number of triangles |
Definition at line 85 of file ColdetModel.cpp.
set the number of vertices
n | the number of vertices |
Definition at line 73 of file ColdetModel.cpp.
set position and orientation of this model
R | new orientation |
p | new position |
Definition at line 258 of file ColdetModel.cpp.
set position and orientation of this model
R | new orientation (length = 9) |
p | new position (length = 3) |
Definition at line 267 of file ColdetModel.cpp.
bool ColdetModel::setPrimitiveParam | ( | unsigned int | index, |
float | value | ||
) |
set a parameter of primitive
index | index of the parameter |
value | value of the parameter |
Definition at line 290 of file ColdetModel.cpp.
set position and orientation of primitive
R | orientation relative to link (length = 9) |
p | position relative to link (length = 3) |
Definition at line 306 of file ColdetModel.cpp.
void ColdetModel::setPrimitiveType | ( | PrimitiveType | ptype | ) |
add a triangle
index | index of the triangle |
v1 | index of the first vertex |
v2 | index of the second vertex |
v3 | index of the third vertex |
Definition at line 119 of file ColdetModel.cpp.
add a vertex
index | index of the vertex |
x | x position of the vertex |
y | y position of the vertex |
z | z position of the vertex |
Definition at line 98 of file ColdetModel.cpp.
|
friend |
Definition at line 265 of file ColdetModel.h.
|
private |
Definition at line 255 of file ColdetModel.h.
|
private |
Definition at line 259 of file ColdetModel.h.
|
private |
Definition at line 258 of file ColdetModel.h.
|
private |
transform of primitive
Definition at line 257 of file ColdetModel.h.
|
private |
Definition at line 256 of file ColdetModel.h.
|
private |
Definition at line 260 of file ColdetModel.h.