#include <GLlink.h>
Public Types | |
enum | { DM_SOLID, DM_WIREFRAME, DM_COLLISION, DM_NUM } |
Public Types inherited from hrp::Link | |
typedef std::vector< ConstraintForce > | ConstraintForceArray |
enum | JointType |
Public Member Functions | |
void | addCamera (GLcamera *camera) |
void | addChild (GLlink *i_child) |
void | addShape (GLshape *shape) |
const std::vector< GLcamera * > & | cameras () |
void | computeAABB (hrp::Vector3 &o_min, hrp::Vector3 &o_max) |
void | computeAbsTransform () |
void | computeAbsTransform (double o_trans[16]) |
void | computeAbsTransform (double o_trans[16]) |
void | divideLargeTriangles (double maxEdgeLen) |
size_t | draw () |
void | draw () |
GLcamera * | findCamera (const char *i_name) |
GLcamera * | findCamera (const char *i_name) |
GLcamera * | findCamera (const char *i_name) |
virtual const aabbox3d< f32 > & | getBoundingBox () const |
GLlink () | |
GLlink (const OpenHRP::LinkInfo &i_li, OpenHRP::BodyInfo_var i_binfo) | |
GLlink (ISceneNode *i_parent, ISceneManager *i_mgr, s32 i_id, const LinkInfo &i_li, BodyInfo_var i_binfo) | |
void | highlight (bool flag) |
int | jointId () |
int | jointId () const |
virtual void | render () |
void | setAbsTransform (double o_trans[16]) |
void | setParent (GLlink *i_parent) |
void | setQ (double i_q) |
void | setQ (double i_q) |
void | setQ (double i_q) |
void | setTransform (double i_trans[16]) |
void | showAxes (bool flag) |
~GLlink () | |
Public Member Functions inherited from hrp::Link | |
void | addChild (Link *link) |
Matrix33 | attitude () |
Matrix33 | calcRfromAttitude (const Matrix33 &R) |
void | calcSubMassCM () |
void | calcSubMassInertia (Matrix33 &subIw) |
bool | detachChild (Link *link) |
bool | isRoot () |
bool | isValid () |
Link () | |
Link (const Link &link) | |
Matrix33 | segmentAttitude () |
void | setAttitude (const Matrix33 &R) |
void | setSegmentAttitude (const Matrix33 &R) |
void | updateColdetModelPosition () |
virtual | ~Link () |
Public Member Functions inherited from GLcoordinates | |
hrp::Vector3 | getPosition () |
void | getPosition (double &x, double &y, double &z) |
hrp::Matrix33 | getRotation () |
void | getRotation (hrp::Matrix33 &R) |
double * | getTransform () |
GLcoordinates () | |
void | setPosition (double x, double y, double z) |
template<class T > | |
void | setPosition (const T &p) |
void | setRotation (double r, double p, double y) |
void | setRotation (double ax, double ay, double az, double th) |
void | setRotation (const hrp::Matrix33 &R) |
void | setRotation (const double *R) |
void | setTransform (const double i_trans[12]) |
Static Public Member Functions | |
static int | drawMode () |
static void | drawMode (int i_mode) |
static void | useAbsTransformToDraw () |
Protected Attributes | |
double | m_absTrans [16] |
std::vector< GLcamera * > | m_cameras |
bool | m_highlight |
std::vector< GLshape * > | m_shapes |
bool | m_showAxes |
double | m_T_j [16] |
Protected Attributes inherited from GLcoordinates | |
double | m_trans [16] |
Static Protected Attributes | |
static int | m_drawMode = GLlink::DM_SOLID |
static bool | m_useAbsTransformToDraw = false |
Private Attributes | |
hrp::Vector3 | m_axis |
Vector3 | m_axis |
aabbox3d< f32 > | m_box |
std::vector< GLcamera * > | m_cameraInfos |
std::vector< GLlink * > | m_children |
int | m_jointId |
int | m_list |
GLlink * | m_parent |
double | m_trans [16] |
anonymous enum |
GLlink::GLlink | ( | ) |
Definition at line 27 of file GLlink.cpp.
GLlink::~GLlink | ( | ) |
Definition at line 34 of file GLlink.cpp.
GLlink::GLlink | ( | const OpenHRP::LinkInfo & | i_li, |
OpenHRP::BodyInfo_var | i_binfo | ||
) |
|
inline |
Definition at line 108 of file IrrModel.cpp.
Definition at line 241 of file GLlink.cpp.
Definition at line 199 of file GLmodel.cpp.
Definition at line 236 of file GLlink.cpp.
Definition at line 256 of file GLlink.cpp.
void GLlink::computeAABB | ( | hrp::Vector3 & | o_min, |
hrp::Vector3 & | o_max | ||
) |
Definition at line 289 of file GLlink.cpp.
void GLlink::computeAbsTransform | ( | ) |
Definition at line 217 of file GLlink.cpp.
void GLlink::computeAbsTransform | ( | double | o_trans[16] | ) |
Definition at line 221 of file GLlink.cpp.
void GLlink::computeAbsTransform | ( | double | o_trans[16] | ) |
void GLlink::divideLargeTriangles | ( | double | maxEdgeLen | ) |
Definition at line 282 of file GLlink.cpp.
void GLlink::draw | ( | ) |
Definition at line 44 of file GLlink.cpp.
void GLlink::draw | ( | ) |
|
static |
Definition at line 261 of file GLlink.cpp.
Definition at line 266 of file GLlink.cpp.
Definition at line 209 of file GLlink.cpp.
Definition at line 323 of file IrrModel.cpp.
|
inlinevirtual |
Definition at line 313 of file IrrModel.cpp.
void GLlink::highlight | ( | bool | flag | ) |
Definition at line 271 of file GLlink.cpp.
int GLlink::jointId | ( | ) |
Definition at line 219 of file GLmodel.cpp.
|
inline |
Definition at line 322 of file IrrModel.cpp.
|
inlinevirtual |
Definition at line 312 of file IrrModel.cpp.
void GLlink::setAbsTransform | ( | double | o_trans[16] | ) |
Definition at line 205 of file GLlink.cpp.
Definition at line 195 of file GLmodel.cpp.
void GLlink::setQ | ( | double | i_q | ) |
Definition at line 169 of file GLlink.cpp.
void GLlink::setQ | ( | double | i_q | ) |
|
inline |
Definition at line 314 of file IrrModel.cpp.
void GLlink::setTransform | ( | double | i_trans[16] | ) |
Definition at line 215 of file GLmodel.cpp.
void GLlink::showAxes | ( | bool | flag | ) |
Definition at line 246 of file GLlink.cpp.
|
static |
Definition at line 22 of file GLlink.cpp.
|
private |
|
private |
Definition at line 331 of file IrrModel.cpp.
|
private |
Definition at line 330 of file IrrModel.cpp.
|
private |
Definition at line 333 of file IrrModel.cpp.
|
staticprotected |
|
staticprotected |