Public Member Functions | Static Public Member Functions | Private Attributes | Static Private Attributes | List of all members
GLbody Class Reference

#include <GLbody.h>

Inheritance diagram for GLbody:
Inheritance graph
[legend]

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)
 
GLcamerafindCamera (const char *i_name)
 
GLcamerafindCamera (const char *i_name)
 
GLcamerafindCamera (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 ()
 
- Public Member Functions inherited from hrp::Body
void addSensor (Sensor *sensor, int sensorType, int id)
 
 Body ()
 
 Body (const Body &org)
 
void calcAngularMomentumJacobian (Link *base, dmatrix &H)
 
Vector3 calcCM ()
 
void calcCMJacobian (Link *base, dmatrix &J)
 
void calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false)
 
void calcInverseDynamics (Link *link, Vector3 &out_f, Vector3 &out_tau)
 
void calcMassMatrix (dmatrix &out_M)
 
double calcTotalMass ()
 
void calcTotalMomentum (Vector3 &out_P, Vector3 &out_L)
 
void calcTotalMomentumFromJacobian (Vector3 &out_P, Vector3 &out_L)
 
void clearExternalForces ()
 
void clearSensorValues ()
 
LightcreateLight (Link *link, int lightType, const std::string &name)
 
SensorcreateSensor (Link *link, int sensorType, int id, const std::string &name)
 
void getDefaultRootPosition (Vector3 &out_p, Matrix33 &out_R)
 
JointPathPtr getJointPath (Link *baseLink, Link *targetLink)
 
void initializeConfiguration ()
 
bool installCustomizer ()
 
bool installCustomizer (BodyCustomizerInterface *customizerInterface)
 
bool isStaticModel ()
 
Linkjoint (int id) const
 
const std::vector< Link * > & joints () const
 
Lightlight (const std::string &name)
 
Linklink (int index) const
 
Linklink (const std::string &name) const
 
const LinkTraverselinks () const
 
const LinkTraverselinkTraverse () const
 
const std::string & modelName ()
 
const std::string & name ()
 
unsigned int numJoints () const
 
unsigned int numLinks () const
 
unsigned int numSensors (int sensorType) const
 
unsigned int numSensorTypes () const
 
void putInformation (std::ostream &out)
 
LinkrootLink () const
 
Sensorsensor (int sensorType, int sensorId) const
 
TSensor * sensor (const std::string &name) const
 
TSensor * sensor (int id) const
 
void setColumnOfMassMatrix (dmatrix &M, int column)
 
void setDefaultRootPosition (const Vector3 &p, const Matrix33 &R)
 
void setModelName (const std::string &name)
 
void setName (const std::string &name)
 
void setRootLink (Link *link)
 
void setVirtualJointForces ()
 
double totalMass () const
 
void updateLinkColdetModelPositions ()
 
void updateLinkTree ()
 
virtual ~Body ()
 
- Public Member Functions inherited from hrp::Referenced
 Referenced ()
 
virtual ~Referenced ()
 

Static Public Member Functions

static void useAbsTransformToDraw ()
 
- Static Public Member Functions inherited from hrp::Body
static BodyInterfacebodyInterface ()
 

Private Attributes

irr::core::aabbox3d< irr::f32 > m_box
 
std::vector< GLlink * > m_links
 
GLlinkm_root
 
boost::function2< void, hrp::Body *, hrp::Sensor * > m_sensorDrawCallback
 

Static Private Attributes

static bool m_useAbsTransformToDraw = false
 

Additional Inherited Members

- Public Types inherited from hrp::Body
enum  ExtraJointType
 
- Public Attributes inherited from hrp::Body
 EJ_XY
 
 EJ_XYZ
 
 EJ_Z
 
std::vector< ExtraJointextraJoints
 
- Protected Member Functions inherited from hrp::Referenced
int refCounter ()
 

Detailed Description

Definition at line 11 of file GLbody.h.

Constructor & Destructor Documentation

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 
)

Member Function Documentation

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
inlinevirtual

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 ( )
inlinevirtual

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.

template<class T >
void GLbody::setPosition ( const T &  p)
inline

Definition at line 19 of file GLbody.h.

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.

Member Data Documentation

irr::core::aabbox3d<irr::f32> GLbody::m_box
private

Definition at line 67 of file IrrModel.h.

std::vector< GLlink * > GLbody::m_links
private

Definition at line 75 of file GLmodel.h.

GLlink * GLbody::m_root
private

Definition at line 74 of file GLmodel.h.

boost::function2<void, hrp::Body *, hrp::Sensor *> GLbody::m_sensorDrawCallback
private

Definition at line 38 of file GLbody.h.

bool GLbody::m_useAbsTransformToDraw = false
staticprivate

Definition at line 37 of file GLbody.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:52