10 #include "hrpsys/util/GLcamera.h"    11 #include "hrpsys/util/GLlink.h"    12 #include "hrpsys/util/GLbody.h"    13 #include "hrpsys/util/LogManager.h"    22     for (
unsigned int i=0; 
i<strlen(str); 
i++){
    23         glutBitmapCharacter(GLUT_BITMAP_8_BY_13, str[
i]);
    28     glColor3d(1.0,1.0,1.0);
    32     glColor3d(1.0,0.0,0.0);
    36     glColor3d(1.0,1.0,0.0);
    40     glColor3d(0.0,1.0,0.0);
    44     glColor3d(0.0,0.0,1.0);
    48     glColor3d(0.0,0.0,0.0);
    52     return s & OpenHRP::RobotHardwareService::CALIB_STATE_MASK; 
    55     return s & OpenHRP::RobotHardwareService::POWER_STATE_MASK; 
    58     return s & OpenHRP::RobotHardwareService::SERVO_STATE_MASK; 
    61     return (s & OpenHRP::RobotHardwareService::SERVO_ALARM_MASK)>>OpenHRP::RobotHardwareService::SERVO_ALARM_SHIFT; 
    64     return (s & OpenHRP::RobotHardwareService::DRIVER_TEMP_MASK)>>OpenHRP::RobotHardwareService::DRIVER_TEMP_SHIFT; 
    69     if (m_log->index()<0) 
return;
    75     if (com.baseTransform.length() == 12){
    76         double *tform = com.baseTransform.get_buffer();
    80         root->
p << tform[0], tform[1], tform[2];
    81         root->
R << tform[3], tform[4], tform[5],
    82             tform[6], tform[7], tform[8],
    83             tform[9], tform[10], tform[11];
    85     if (com.jointRefs.length() == glbody->
numJoints()){
    89                 j->
q = com.jointRefs[
i];
    90                 j->
setQ(com.jointRefs[
i]);
    99     for (
size_t i=0; 
i<m_pairs.size(); 
i++){
   100         if (m_pairs[
i]->checkCollision()){
   101             ((
GLlink *)m_pairs[
i]->link(0))->highlight(
true);
   102             ((
GLlink *)m_pairs[
i]->link(1))->highlight(
true);
   103             std::cout << m_pairs[
i]->link(0)->name << 
"<->" << m_pairs[
i]->link(1)->name << std::endl;
   110     if (m_log->index()<0) 
return;
   114     OpenHRP::RobotHardwareService::RobotState &rstate = lm->
state().
state;
   116     if (m_showingStatus){
   118 #define HEIGHT_STEP 12   119         int width = m_width - 410;
   125                 int ss = rstate.servoState[
i][0];
   134                 glRasterPos2f(x, height);
   140                 glRasterPos2f(x, height);
   145                 sprintf(buf, 
"%13s %8.3f %8.3f %6.1f", 
   147                         (
i<rstate.angle.length())?(rstate.angle[
i]*180/
M_PI):0,
   148                         (
i<rstate.command.length())?(rstate.command[
i]*180/
M_PI):0,
   149                         (
i<rstate.torque.length())?(rstate.torque[
i]*180/
M_PI):0);
   150                 glRasterPos2f(x, height);
   156                 glRasterPos2f(x, height);
   166                 if (temp >= 60) 
red();
   167                 glRasterPos2f(x, height);
   169                 if (temp >= 60) 
white();
   175         if (rstate.accel.length()){
   176             glRasterPos2f(width, height);
   179             for (
unsigned int i=0; 
i<rstate.accel.length(); 
i++){
   180                 sprintf(buf, 
"  %8.4f %8.4f %8.4f",
   181                         rstate.accel[
i][0], rstate.accel[
i][1], rstate.accel[
i][2]);
   182                 glRasterPos2f(width, height);
   187         if (rstate.rateGyro.length()){
   188             glRasterPos2f(width, height);
   191             for (
unsigned int i=0; 
i<rstate.rateGyro.length(); 
i++){
   192                 sprintf(buf, 
"  %8.4f %8.4f %8.4f",
   193                         rstate.rateGyro[
i][0], rstate.rateGyro[
i][1], rstate.rateGyro[
i][2]);
   194                 glRasterPos2f(width, height);
   199         if (rstate.force.length()){
   200             glRasterPos2f(width, height);
   203             for (
unsigned int i=0; 
i<rstate.force.length(); 
i++){
   204                 sprintf(buf, 
"  %6.1f %6.1f %6.1f %6.2f %6.2f %6.2f",
   211                 glRasterPos2f(width, height);
   216         glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
   218         glColor4f(0.0,0.0,0.0, 0.5);
   222             glRectf(width,0,m_width,m_height);
   228         for (
unsigned int i=0; 
i<rstate.servoState.length(); 
i++){
   229             if (
isServoOn(rstate.servoState[
i][0])) servo = 
true;
   234         double dt = tv.tv_sec + tv.tv_usec/1e6 - lm->
time(m_log->length()-1);
   236         glRectf(m_width-115,m_height-45,m_width-85,m_height-15);
   238         glRectf(m_width- 80,m_height-45,m_width-50,m_height-15);
   240         glRectf(m_width- 45,m_height-45,m_width-15,m_height-15);
   246     for (
int i=0; 
i<4; 
i++){
   247         for (
int j=0; 
j<4; 
j++){
   248             printf(
"%6.3f ", mat[
j*4+
i]);
   256 #define LINE_HLEN 0.5   258     v[0] = p[0]+
LINE_HLEN; v[1] = p[1]; v[2] = p[2]+0.001;
   262     v[0] = p[0]; v[1] = p[1]+
LINE_HLEN; v[2] = p[2]+0.001;
   266     v[0] = p[0]; v[1] = p[1]; v[2] = p[2]+0.001;
   274     if (m_log->index()<0) 
return;
   280     if (com.zmp.length() != 3) 
return;
   282     Vector3 relZmp(com.zmp[0], com.zmp[1], com.zmp[2]);
   284     Vector3 absZmp = root->
R*relZmp + root->
p;
   288     if (m_showCoMonFloor){
   305     m_showCoMonFloor = flag;
 
void setPosition(double x, double y, double z)
void setCollisionCheckPairs(const std::vector< hrp::ColdetLinkPairPtr > &i_pairs)
static void drawCross(const Vector3 &p)
void drawAdditionalLines()
void showCoMonFloor(bool flag)
png_infop png_uint_32 * width
OpenHRP::RobotHardwareService::RobotState state
void setRotation(const double *R)
void printMatrix(double mat[16])
int gettimeofday(struct timeval *tv, struct timezone *tz)
void updateLinkColdetModelPositions()
png_infop png_uint_32 png_uint_32 * height
def j(str, encoding="cp932")
void drawString2(const char *str)
Link * joint(int id) const 
static std::vector< int > servo
Link * link(int index) const 
OpenHRP::StateHolderService::Command command
std::string sprintf(char const *__restrict fmt,...)
unsigned int numJoints() const 
static std::vector< int > power
unsigned int numLinks() const 
#define SLIDER_AREA_HEIGHT
void calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false)