#include <GLbody.h>
Public Member Functions | |
void | computeAABB (hrp::Vector3 &o_min, hrp::Vector3 &o_max) |
void | divideLargeTriangles (double maxEdgeLen) |
size_t | draw () |
void | draw () |
void | drawSensor (hrp::Sensor *i_sensor) |
GLcamera * | findCamera (const char *i_name) |
GLcamera * | findCamera (const char *i_name) |
GLcamera * | findCamera (const char *i_name) |
virtual const irr::core::aabbox3d< irr::f32 > & | getBoundingBox () const |
boost::function2< void, hrp::Body *, hrp::Sensor * > | getSensorDrawCallback () |
GLbody () | |
GLbody (irr::scene::ISceneNode *i_parent, irr::scene::ISceneManager *i_mgr, irr::s32 i_id, OpenHRP::BodyInfo_var i_binfo) | |
GLbody (OpenHRP::BodyInfo_var i_binfo) | |
virtual void | render () |
void | setPosition (double x, double y, double z) |
template<class T > | |
void | setPosition (const T &p) |
void | setPosture (const double *i_angles) |
void | setPosture (const double *i_angles, double *i_pos, double *i_rpy) |
void | setPosture (const hrp::dvector &i_q, const hrp::Vector3 &i_p, const hrp::Matrix33 &i_R) |
void | setPosture (double *i_angles, double *i_pos, double *i_rpy) |
void | setPosture (double *i_angles, double *i_pos, double *i_rpy) |
void | setRotation (const double *R) |
void | setRotation (double r, double p, double y) |
void | setSensorDrawCallback (boost::function2< void, hrp::Body *, hrp::Sensor * > f) |
~GLbody () | |
~GLbody () | |
Static Public Member Functions | |
static void | useAbsTransformToDraw () |
Private Attributes | |
irr::core::aabbox3d< irr::f32 > | m_box |
std::vector< GLlink * > | m_links |
GLlink * | m_root |
boost::function2< void, hrp::Body *, hrp::Sensor * > | m_sensorDrawCallback |
Static Private Attributes | |
static bool | m_useAbsTransformToDraw = false |
GLbody::GLbody | ( | ) |
Definition at line 14 of file GLbody.cpp.
GLbody::~GLbody | ( | ) |
Definition at line 18 of file GLbody.cpp.
GLbody::GLbody | ( | OpenHRP::BodyInfo_var | i_binfo | ) |
GLbody::~GLbody | ( | ) |
GLbody::GLbody | ( | irr::scene::ISceneNode * | i_parent, |
irr::scene::ISceneManager * | i_mgr, | ||
irr::s32 | i_id, | ||
OpenHRP::BodyInfo_var | i_binfo | ||
) |
void GLbody::computeAABB | ( | hrp::Vector3 & | o_min, |
hrp::Vector3 & | o_max | ||
) |
Definition at line 102 of file GLbody.cpp.
void GLbody::divideLargeTriangles | ( | double | maxEdgeLen | ) |
Definition at line 94 of file GLbody.cpp.
void GLbody::draw | ( | ) |
Definition at line 59 of file GLbody.cpp.
void GLbody::draw | ( | ) |
void GLbody::drawSensor | ( | hrp::Sensor * | i_sensor | ) |
Definition at line 79 of file GLbody.cpp.
GLcamera * GLbody::findCamera | ( | const char * | i_name | ) |
Definition at line 71 of file GLbody.cpp.
GLcamera* GLbody::findCamera | ( | const char * | i_name | ) |
GLcamera* GLbody::findCamera | ( | const char * | i_name | ) |
virtual const irr::core::aabbox3d<irr::f32>& GLbody::getBoundingBox | ( | ) | const [inline, virtual] |
Definition at line 61 of file IrrModel.h.
boost::function2< void, hrp::Body *, hrp::Sensor * > GLbody::getSensorDrawCallback | ( | ) |
Definition at line 89 of file GLbody.cpp.
virtual void GLbody::render | ( | ) | [inline, virtual] |
Definition at line 60 of file IrrModel.h.
void GLbody::setPosition | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 27 of file GLbody.cpp.
void GLbody::setPosition | ( | const T & | p | ) | [inline] |
void GLbody::setPosture | ( | const double * | i_angles | ) |
Definition at line 21 of file GLbody.cpp.
void GLbody::setPosture | ( | const double * | i_angles, |
double * | i_pos, | ||
double * | i_rpy | ||
) |
Definition at line 42 of file GLbody.cpp.
void GLbody::setPosture | ( | const hrp::dvector & | i_q, |
const hrp::Vector3 & | i_p, | ||
const hrp::Matrix33 & | i_R | ||
) |
void GLbody::setPosture | ( | double * | i_angles, |
double * | i_pos, | ||
double * | i_rpy | ||
) |
void GLbody::setPosture | ( | double * | i_angles, |
double * | i_pos, | ||
double * | i_rpy | ||
) |
Definition at line 265 of file GLmodel.cpp.
void GLbody::setRotation | ( | const double * | R | ) |
Definition at line 37 of file GLbody.cpp.
void GLbody::setRotation | ( | double | r, |
double | p, | ||
double | y | ||
) |
Definition at line 32 of file GLbody.cpp.
void GLbody::setSensorDrawCallback | ( | boost::function2< void, hrp::Body *, hrp::Sensor * > | f | ) |
Definition at line 84 of file GLbody.cpp.
void GLbody::useAbsTransformToDraw | ( | ) | [static] |
Definition at line 9 of file GLbody.cpp.
irr::core::aabbox3d<irr::f32> GLbody::m_box [private] |
Definition at line 67 of file IrrModel.h.
std::vector< GLlink * > GLbody::m_links [private] |
GLlink * GLbody::m_root [private] |
boost::function2<void, hrp::Body *, hrp::Sensor *> GLbody::m_sensorDrawCallback [private] |
bool GLbody::m_useAbsTransformToDraw = false [static, private] |