Public Types | Public Member Functions | Private Member Functions | Private Attributes | Friends
hrp::ColdetModel Class Reference

#include <ColdetModel.h>

Inheritance diagram for hrp::ColdetModel:
Inheritance graph
[legend]

List of all members.

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
bool checkCollisionWithPointCloud (const std::vector< Vector3 > &i_cloud, double i_radius)
 check collision between this triangle mesh and a point cloud
 ColdetModel ()
 constructor
 ColdetModel (const ColdetModel &org)
 copy constructor
double computeDistanceWithRay (const double *point, const double *dir)
 compute distance between a point and this mesh along ray
int getAABBmaxNum ()
int getAABBTreeDepth ()
void getBoundingBoxData (const int depth, std::vector< Vector3 > &out_boxes)
ColdetModelSharedDataSetgetDataSet ()
int getNumTriangles () const
int getNumVertices () const
 get the number of vertices
bool getPrimitiveParam (unsigned int index, float &value) const
 get a parameter of primitive
PrimitiveType getPrimitiveType () const
 get primitive type
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
bool isValid () const
 check if build() is already called or not
const std::string & name () const
 get name of this model
int numofBBtoDepth (int minNumofBB)
void setName (const std::string &name)
 set name of this model
void setNumPrimitiveParams (unsigned int nparam)
 set the number of parameters of primitive
void setNumTriangles (int n)
 set the number of triangles
void setNumVertices (int n)
 set the number of vertices
void setPosition (const Matrix33 &R, const Vector3 &p)
 set position and orientation of this model
void setPosition (const double *R, const double *p)
 set position and orientation of this model
bool setPrimitiveParam (unsigned int index, float value)
 set a parameter of primitive
void setPrimitivePosition (const double *R, const double *p)
 set position and orientation of primitive
void setPrimitiveType (PrimitiveType ptype)
 set primitive type
void setTriangle (int index, int v1, int v2, int v3)
 add a triangle
void setVertex (int index, float x, float y, float z)
 add a vertex
virtual ~ColdetModel ()
 destructor

Private Member Functions

void initialize ()
 common part of constuctors
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

ColdetModelSharedDataSetdataSet
bool isValid_
std::string name_
IceMaths::Matrix4x4pTransform
 transform of primitive
IceMaths::Matrix4x4transform
EdgeToTriangleMap triangleMap

Friends

class ColdetModelPair

Detailed Description

Definition at line 61 of file ColdetModel.h.


Member Enumeration Documentation

Enumerator:
SP_MESH 
SP_BOX 
SP_CYLINDER 
SP_CONE 
SP_SPHERE 
SP_PLANE 

Definition at line 64 of file ColdetModel.h.


Constructor & Destructor Documentation

constructor

Definition at line 24 of file ColdetModel.cpp.

copy constructor

Shape information stored in dataSet is shared with org

Definition at line 34 of file ColdetModel.cpp.

destructor

Definition at line 63 of file ColdetModel.cpp.


Member Function Documentation

void ColdetModel::addTriangle ( int  v1,
int  v2,
int  v3 
)

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.

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

Parameters:
i_cloudpoints
i_radiusradius of spheres assigned to the points
Returns:
true if colliding, false otherwise

Definition at line 331 of file ColdetModel.cpp.

double ColdetModel::computeDistanceWithRay ( const double *  point,
const double *  dir 
)

compute distance between a point and this mesh along ray

Parameters:
pointa point
dirdirection of ray
Returns:
distance if ray collides with this mesh, FLT_MAX otherwise

Definition at line 314 of file ColdetModel.cpp.

Definition at line 201 of file ColdetModel.cpp.

Definition at line 197 of file ColdetModel.cpp.

void ColdetModel::getBoundingBoxData ( const int  depth,
std::vector< Vector3 > &  out_boxes 
)

Definition at line 223 of file ColdetModel.cpp.

Definition at line 245 of file ColdetModel.h.

Definition at line 92 of file ColdetModel.cpp.

get the number of vertices

Returns:
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

Parameters:
indexindex of the parameter
valuevalue of the parameter
Returns:
true if the parameter is gotten successfully, false otherwise

Definition at line 298 of file ColdetModel.cpp.

get primitive type

Returns:
primitive type

Definition at line 280 of file ColdetModel.cpp.

void ColdetModel::getTriangle ( int  index,
int out_v1,
int out_v2,
int out_v3 
) const

Definition at line 128 of file ColdetModel.cpp.

void ColdetModel::getVertex ( int  index,
float &  out_x,
float &  out_y,
float &  out_z 
) const

get a vertex

Parameters:
indexindex of the vertex
out_xx position of the vertex
out_yy position of the vertex
out_zz position of the vertex

Definition at line 110 of file ColdetModel.cpp.

common part of constuctors

Definition at line 43 of file ColdetModel.cpp.

Definition at line 383 of file ColdetModel.cpp.

bool hrp::ColdetModel::isValid ( ) const [inline]

check if build() is already called or not

Returns:
true if build() is already called, false otherwise

Definition at line 165 of file ColdetModel.h.

const std::string& hrp::ColdetModel::name ( ) const [inline]

get name of this model

Returns:
name name of this model

Definition at line 93 of file ColdetModel.h.

Definition at line 190 of file ColdetModel.cpp.

void hrp::ColdetModel::setName ( const std::string &  name) [inline]

set name of this model

Parameters:
namename of this model

Definition at line 87 of file ColdetModel.h.

void ColdetModel::setNeighbor ( int  triangle0,
int  triangle1 
) [private]

Definition at line 387 of file ColdetModel.cpp.

void ColdetModel::setNeighborTriangle ( int  triangle,
int  vertex0,
int  vertex1,
int  vertex2 
) [private]

Definition at line 351 of file ColdetModel.cpp.

bool ColdetModel::setNeighborTriangleSub ( int  triangle,
int  vertex0,
int  vertex1 
) [private]

Definition at line 357 of file ColdetModel.cpp.

set the number of parameters of primitive

Parameters:
nparamthe number of parameters of primitive

Definition at line 285 of file ColdetModel.cpp.

set the number of triangles

Parameters:
nthe number of triangles

Definition at line 85 of file ColdetModel.cpp.

set the number of vertices

Parameters:
nthe number of vertices

Definition at line 73 of file ColdetModel.cpp.

set position and orientation of this model

Parameters:
Rnew orientation
pnew position

Definition at line 258 of file ColdetModel.cpp.

void ColdetModel::setPosition ( const double *  R,
const double *  p 
)

set position and orientation of this model

Parameters:
Rnew orientation (length = 9)
pnew position (length = 3)

Definition at line 267 of file ColdetModel.cpp.

bool ColdetModel::setPrimitiveParam ( unsigned int  index,
float  value 
)

set a parameter of primitive

Parameters:
indexindex of the parameter
valuevalue of the parameter
Returns:
true if the parameter is set successfully, false otherwise

Definition at line 290 of file ColdetModel.cpp.

void ColdetModel::setPrimitivePosition ( const double *  R,
const double *  p 
)

set position and orientation of primitive

Parameters:
Rorientation relative to link (length = 9)
pposition relative to link (length = 3)

Definition at line 306 of file ColdetModel.cpp.

set primitive type

Parameters:
ptypeprimitive type

Definition at line 275 of file ColdetModel.cpp.

void ColdetModel::setTriangle ( int  index,
int  v1,
int  v2,
int  v3 
)

add a triangle

Parameters:
indexindex of the triangle
v1index of the first vertex
v2index of the second vertex
v3index of the third vertex

Definition at line 119 of file ColdetModel.cpp.

void ColdetModel::setVertex ( int  index,
float  x,
float  y,
float  z 
)

add a vertex

Parameters:
indexindex of the vertex
xx position of the vertex
yy position of the vertex
zz position of the vertex

Definition at line 98 of file ColdetModel.cpp.


Friends And Related Function Documentation

friend class ColdetModelPair [friend]

Definition at line 265 of file ColdetModel.h.


Member Data Documentation

Definition at line 255 of file ColdetModel.h.

Definition at line 259 of file ColdetModel.h.

std::string hrp::ColdetModel::name_ [private]

Definition at line 258 of file ColdetModel.h.

transform of primitive

Definition at line 257 of file ColdetModel.h.

Definition at line 256 of file ColdetModel.h.

Definition at line 260 of file ColdetModel.h.


The documentation for this class was generated from the following files:


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Thu Apr 11 2019 03:30:22