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

#include <GLmodel.h>

Inheritance diagram for GLscene:
Inheritance graph
[legend]

Public Member Functions

GLbodyaddBody (OpenHRP::BodyInfo_var i_binfo)
 
void addBody (GLbody *i_body)
 
GLbodybody (unsigned int i_rank)
 
void capture (unsigned char *o_image)
 
void draw ()
 
void draw (bool swap=true)
 
GLcameragetCamera ()
 
GLcameragetCamera ()
 
irr::scene::ISceneManager * getSceneManager ()
 
irr::video::IVideoDriver * getVideoDriver ()
 
 GLscene (LogManagerBase *i_log)
 
 GLscene (LogManagerBase *i_log)
 
 GLscene (LogManagerBase *i_log)
 
 GLscene (LogManagerBase *i_log)
 
 GLscene (LogManagerBase *i_log)
 
 GLscene ()
 
bool init (int w=640, int h=480)
 
void init ()
 
unsigned int numBodies () const
 
void save (const char *i_fname)
 
void setCamera (GLcamera *i_camera)
 
void setCamera (GLcamera *i_camera)
 
void setCollisionCheckPairs (const std::vector< hrp::ColdetLinkPairPtr > &i_pairs)
 
void showCollision (bool flag)
 
bool showCollision ()
 
void showCoMonFloor (bool flag)
 
void showSensors (bool flag)
 
bool showSensors ()
 
 ~GLscene ()
 
 ~GLscene ()
 
- Public Member Functions inherited from GLsceneBase
void addBody (hrp::BodyPtr i_body)
 
void capture (char *o_image)
 
void capture ()
 
hrp::Vector3 center ()
 
void clear ()
 
void defaultLights (bool flag)
 
bool defaultLights ()
 
void draw ()
 
size_t drawObjects (bool showSensors=true)
 
GLcameragetCamera ()
 
GLcameragetDefaultCamera ()
 
 GLsceneBase (LogManagerBase *i_log)
 
void init ()
 
void initLights ()
 
void maxEdgeLen (double i_len)
 
void nextCamera ()
 
void nextObject ()
 
void requestCapture (const char *i_fname)
 
void requestClear ()
 
void save (const char *i_fname)
 
void setBackGroundColor (float rgb[3])
 
void setCamera (GLcamera *i_camera)
 
void setMessages (const std::vector< std::string > &i_msgs)
 
void setScreenSize (int w, int h)
 
void setView ()
 
void showFloorGrid (bool flag)
 
bool showFloorGrid ()
 
void showInfo (bool flag)
 
void showSlider (bool flag)
 
hrp::BodyPtr targetObject ()
 
void toggleRobotState ()
 
virtual ~GLsceneBase ()
 
- Public Member Functions inherited from hrp::World< hrp::ConstraintForceSolver >
virtual void calcNextState (OpenHRP::CollisionSequence &corbaCollisionSequence)
 
virtual void initialize ()
 
 World ()
 
- Public Member Functions inherited from hrp::WorldBase
int addBody (BodyPtr body)
 
BodyPtr body (int index)
 
BodyPtr body (const std::string &name)
 
int bodyIndex (const std::string &name)
 
virtual void calcNextState ()
 
void clearBodies ()
 
void clearCollisionPairs ()
 
double currentTime (void) const
 
void enableSensors (bool on)
 
ForwardDynamicsPtr forwardDynamics (int index)
 
const Vector3getGravityAcceleration ()
 
std::pair< int, bool > getIndexOfLinkPairs (Link *link1, Link *link2)
 
unsigned int numBodies ()
 
void setCurrentTime (double tm)
 
void setEulerMethod ()
 
void setGravityAcceleration (const Vector3 &g)
 
void setRungeKuttaMethod ()
 
void setTimeStep (double dt)
 
double timeStep (void) const
 
 WorldBase ()
 
virtual ~WorldBase ()
 

Static Public Member Functions

static GLscenegetInstance ()
 
static GLscenegetInstance ()
 

Private Member Functions

void drawAdditionalLines ()
 
void drawAdditionalLines ()
 
void drawAdditionalLines ()
 
void drawSensorOutput (hrp::Body *i_body, hrp::Sensor *i_sensor)
 
 GLscene ()
 
void showStatus ()
 
void showStatus ()
 
void showStatus ()
 
void showStatus ()
 
void updateScene ()
 
void updateScene ()
 
void updateScene ()
 
void updateScene ()
 
void updateScene ()
 
 ~GLscene ()
 

Private Attributes

std::vector< GLbody * > m_bodies
 
GLcameram_camera
 
irr::scene::ICameraSceneNode * m_cnode
 
GLcameram_default_camera
 
GLcameram_defaultCamera
 
irr::IrrlichtDevice * m_device
 
std::vector< hrp::ColdetLinkPairPtrm_pairs
 
irr::IEventReceiver * m_receiver
 
bool m_showCollision
 
bool m_showCoMonFloor
 
bool m_showSensors
 

Static Private Attributes

static GLscenem_scene = new GLscene()
 

Additional Inherited Members

- Public Attributes inherited from hrp::World< hrp::ConstraintForceSolver >
hrp::ConstraintForceSolver constraintForceSolver
 
- Protected Types inherited from GLsceneBase
enum  { REQ_NONE, REQ_CLEAR, REQ_CAPTURE }
 
- Protected Member Functions inherited from GLsceneBase
void drawFloorGrid ()
 
void drawInfo (double fps, size_t ntri)
 
- Protected Attributes inherited from GLsceneBase
float m_bgColor [3]
 
GLcameram_camera
 
IplImage * m_cvImage
 
GLcameram_default_camera
 
bool m_defaultLights
 
std::string m_fname
 
int m_height
 
bool m_isCapturing
 
struct timeval m_lastDraw
 
LogManagerBasem_log
 
double m_maxEdgeLen
 
std::vector< std::string > m_msgs
 
int m_request
 
SDL_sem * m_sem
 
bool m_showFloorGrid
 
bool m_showInfo
 
bool m_showingStatus
 
bool m_showSlider
 
int m_targetObject
 
CvVideoWriter * m_videoWriter
 
int m_width
 
- Protected Attributes inherited from hrp::WorldBase
std::vector< BodyInfo > bodyInfoArray
 
double currentTime_
 
bool sensorsAreEnabled
 
double timeStep_
 

Detailed Description

Definition at line 78 of file GLmodel.h.

Constructor & Destructor Documentation

GLscene::GLscene ( )
private

Definition at line 347 of file GLmodel.cpp.

GLscene::~GLscene ( )
private

Definition at line 357 of file GLmodel.cpp.

GLscene::GLscene ( )
GLscene::~GLscene ( )
GLscene::GLscene ( LogManagerBase i_log)
inline

Definition at line 11 of file rtc/Viewer/GLscene.h.

GLscene::GLscene ( LogManagerBase i_log)
inline

Definition at line 11 of file rtc/VirtualCamera/GLscene.h.

GLscene::GLscene ( LogManagerBase i_log)
inline

Definition at line 12 of file util/monitor/GLscene.h.

GLscene::GLscene ( LogManagerBase i_log)
GLscene::GLscene ( LogManagerBase i_log)
GLscene::~GLscene ( )

Member Function Documentation

GLbody * GLscene::addBody ( OpenHRP::BodyInfo_var  i_binfo)

Definition at line 550 of file IrrModel.cpp.

void GLscene::addBody ( GLbody i_body)

Definition at line 293 of file GLmodel.cpp.

GLbody * GLscene::body ( unsigned int  i_rank)

Definition at line 442 of file GLmodel.cpp.

void GLscene::capture ( unsigned char *  o_image)

Definition at line 408 of file GLmodel.cpp.

void GLscene::draw ( )

Definition at line 496 of file IrrModel.cpp.

void GLscene::draw ( bool  swap = true)

Definition at line 297 of file GLmodel.cpp.

void GLscene::drawAdditionalLines ( )
privatevirtual

Reimplemented from GLsceneBase.

void GLscene::drawAdditionalLines ( )
privatevirtual

Reimplemented from GLsceneBase.

void GLscene::drawAdditionalLines ( )
privatevirtual

Reimplemented from GLsceneBase.

Definition at line 272 of file util/monitor/GLscene.cpp.

void GLscene::drawSensorOutput ( hrp::Body i_body,
hrp::Sensor i_sensor 
)
private

Definition at line 171 of file util/simulator/GLscene.cpp.

GLcamera* GLscene::getCamera ( )
GLcamera * GLscene::getCamera ( )

Definition at line 429 of file GLmodel.cpp.

static GLscene* GLscene::getInstance ( )
static
GLscene * GLscene::getInstance ( )
static

Definition at line 332 of file GLmodel.cpp.

ISceneManager * GLscene::getSceneManager ( )

Definition at line 572 of file IrrModel.cpp.

IVideoDriver * GLscene::getVideoDriver ( )

Definition at line 577 of file IrrModel.cpp.

bool GLscene::init ( int  w = 640,
int  h = 480 
)

Definition at line 524 of file IrrModel.cpp.

void GLscene::init ( )

Definition at line 362 of file GLmodel.cpp.

unsigned int GLscene::numBodies ( ) const

Definition at line 437 of file GLmodel.cpp.

void GLscene::save ( const char *  i_fname)

Definition at line 391 of file GLmodel.cpp.

void GLscene::setCamera ( GLcamera i_camera)
void GLscene::setCamera ( GLcamera i_camera)

Definition at line 420 of file GLmodel.cpp.

void GLscene::setCollisionCheckPairs ( const std::vector< hrp::ColdetLinkPairPtr > &  i_pairs)

Definition at line 298 of file util/monitor/GLscene.cpp.

void GLscene::showCollision ( bool  flag)

Definition at line 261 of file util/simulator/GLscene.cpp.

bool GLscene::showCollision ( )

Definition at line 266 of file util/simulator/GLscene.cpp.

void GLscene::showCoMonFloor ( bool  flag)

Definition at line 303 of file util/monitor/GLscene.cpp.

void GLscene::showSensors ( bool  flag)

Definition at line 251 of file util/simulator/GLscene.cpp.

bool GLscene::showSensors ( )

Definition at line 256 of file util/simulator/GLscene.cpp.

void GLscene::showStatus ( )
privatevirtual

Reimplemented from GLsceneBase.

void GLscene::showStatus ( )
privatevirtual

Reimplemented from GLsceneBase.

Definition at line 71 of file rtc/Viewer/GLscene.cpp.

void GLscene::showStatus ( )
privatevirtual

Reimplemented from GLsceneBase.

void GLscene::showStatus ( )
privatevirtual

Reimplemented from GLsceneBase.

void GLscene::updateScene ( )
privatevirtual

Implements GLsceneBase.

Definition at line 51 of file rtc/Viewer/GLscene.cpp.

void GLscene::updateScene ( )
privatevirtual

Implements GLsceneBase.

void GLscene::updateScene ( )
privatevirtual

Implements GLsceneBase.

void GLscene::updateScene ( )
privatevirtual

Implements GLsceneBase.

void GLscene::updateScene ( )
privatevirtual

Implements GLsceneBase.

Member Data Documentation

std::vector<GLbody *> GLscene::m_bodies
private

Definition at line 97 of file GLmodel.h.

GLcamera * GLscene::m_camera
private

Definition at line 98 of file GLmodel.h.

irr::scene::ICameraSceneNode* GLscene::m_cnode
private

Definition at line 28 of file IrrModel.h.

GLcamera * GLscene::m_default_camera
private

Definition at line 98 of file GLmodel.h.

GLcamera * GLscene::m_defaultCamera
private

Definition at line 27 of file IrrModel.h.

irr::IrrlichtDevice* GLscene::m_device
private

Definition at line 26 of file IrrModel.h.

std::vector<hrp::ColdetLinkPairPtr> GLscene::m_pairs
private

Definition at line 19 of file util/monitor/GLscene.h.

irr::IEventReceiver* GLscene::m_receiver
private

Definition at line 29 of file IrrModel.h.

static GLscene * GLscene::m_scene = new GLscene()
staticprivate

Definition at line 96 of file GLmodel.h.

bool GLscene::m_showCollision
private

Definition at line 20 of file util/simulator/GLscene.h.

bool GLscene::m_showCoMonFloor
private

Definition at line 20 of file util/monitor/GLscene.h.

bool GLscene::m_showSensors
private

Definition at line 20 of file util/simulator/GLscene.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