robot.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <cstdio>
00003 #include <cstring>
00004 #include <fstream>
00005 #include <sys/time.h>
00006 #include <hrpModel/Sensor.h>
00007 #include <hrpModel/Link.h>
00008 #include "defs.h"
00009 #include "hrpsys/io/iob.h"
00010 #include "robot.h"
00011 #include "hrpsys/util/Hrpsys.h"
00012 
00013 #define CALIB_COUNT     (10*200)
00014 #define GAIN_COUNT      ( 5*200)
00015 
00016 #define DEFAULT_MAX_ZMP_ERROR 0.03 //[m]
00017 #define DEFAULT_ANGLE_ERROR_LIMIT 0.2 // [rad]
00018 
00019 using namespace hrp;
00020 
00021 
00022 robot::robot(double dt) : m_fzLimitRatio(0), m_maxZmpError(DEFAULT_MAX_ZMP_ERROR), m_accLimit(0), m_calibRequested(false), m_pdgainsFilename("PDgains.sav"), m_reportedEmergency(true), m_dt(dt), m_enable_poweroff_check(false),m_servoOnDelay(0)
00023 {
00024     sem_init(&wait_sem, 0, 0);
00025     m_rLegForceSensorId = m_lLegForceSensorId = -1;
00026 }
00027 
00028 robot::~robot()
00029 {
00030     close_iob();
00031 }
00032 
00033 bool robot::init()
00034 {
00035     int i;
00036     gain_counter.resize(numJoints());
00037     for (unsigned i=0; i<numJoints(); i++){
00038         gain_counter[i] = GAIN_COUNT;
00039     }
00040 
00041     inertia_calib_counter = force_calib_counter = -1;
00042 
00043     pgain.resize(numJoints());
00044     dgain.resize(numJoints());
00045     old_pgain.resize(numJoints());
00046     old_dgain.resize(numJoints());
00047     default_pgain.resize(numJoints());
00048     default_dgain.resize(numJoints());
00049     tqpgain.resize(numJoints());
00050     tqdgain.resize(numJoints());
00051     old_tqpgain.resize(numJoints());
00052     old_tqdgain.resize(numJoints());
00053     default_tqpgain.resize(numJoints());
00054     default_tqdgain.resize(numJoints());
00055     for (unsigned int i=0; i<numJoints(); i++){
00056         pgain[i] = dgain[i] = 0.0;
00057         old_pgain[i] = old_dgain[i] = 0.0;
00058         default_pgain[i] = default_dgain[i] = 0.0;
00059         tqpgain[i] = tqdgain[i] = 0.0;
00060         old_tqpgain[i] = old_tqdgain[i] = 0.0;
00061         default_tqpgain[i] = default_tqdgain[i] = 0.0;
00062     } 
00063     loadGain();
00064     for (unsigned int i=0; i<numJoints(); i++){
00065         pgain[i] = default_pgain[i];
00066         dgain[i] = default_dgain[i];
00067         tqpgain[i] = default_tqpgain[i];
00068         tqdgain[i] = default_tqdgain[i];
00069     }
00070 
00071     m_servoErrorLimit.resize(numJoints());
00072     for (unsigned int i=0; i<numJoints(); i++){
00073         m_servoErrorLimit[i] = DEFAULT_ANGLE_ERROR_LIMIT;
00074     }
00075 
00076 
00077 
00078     set_number_of_joints(numJoints());
00079     set_number_of_force_sensors(numSensors(Sensor::FORCE));
00080     set_number_of_gyro_sensors(numSensors(Sensor::RATE_GYRO));
00081     set_number_of_accelerometers(numSensors(Sensor::ACCELERATION));
00082 
00083     gyro_sum.resize(numSensors(Sensor::RATE_GYRO));
00084     accel_sum.resize(numSensors(Sensor::ACCELERATION));
00085     force_sum.resize(numSensors(Sensor::FORCE));
00086 
00087     if ((number_of_joints() != (int)numJoints())
00088         || (number_of_force_sensors() != (int)numSensors(Sensor::FORCE))
00089         || (number_of_gyro_sensors() != (int)numSensors(Sensor::RATE_GYRO))
00090         || (number_of_accelerometers() != (int)numSensors(Sensor::ACCELERATION))){
00091       std::cerr << "VRML and IOB are inconsistent" << std::endl;
00092       std::cerr << "  joints:" << numJoints() << "(VRML), " << number_of_joints() << "(IOB)"  << std::endl;
00093       std::cerr << "  force sensor:" << numSensors(Sensor::FORCE) << "(VRML), " << number_of_force_sensors() << "(IOB)"  << std::endl;
00094       std::cerr << "  gyro sensor:" << numSensors(Sensor::RATE_GYRO) << "(VRML), " << number_of_gyro_sensors() << "(IOB)"  << std::endl;
00095       std::cerr << "  accelerometer:" << numSensors(Sensor::ACCELERATION) << "(VRML), " << number_of_accelerometers() << "(IOB)"  << std::endl;
00096       return false;
00097     }
00098     G << 0, 0, 9.8;
00099 
00100     if (open_iob() == FALSE) return false;
00101 
00102     return true;
00103 }
00104 
00105 void robot::removeForceSensorOffset()
00106 {
00107     std::cerr << "[RobotHardware] removeForceSensorOffset..." << std::endl;
00108     startForceSensorCalibration();
00109     std::cerr << "[RobotHardware] removeForceSensorOffset...done." << std::endl;
00110 }
00111 
00112 bool robot::loadGain()
00113 {
00114     std::ifstream strm(m_pdgainsFilename.c_str());
00115     if (!strm.is_open()) {
00116         std::cerr << m_pdgainsFilename << " not found" << std::endl;
00117         return false;
00118     }
00119 
00120     for (int i = 0; i < numJoints(); i++) {
00121         std::string str;
00122         bool getlinep;
00123         while ((getlinep = !!(std::getline(strm, str)))) {
00124             if (str.empty())   {
00125                 // std::cerr << "[RobotHardware] : loadGain : skip emptiy line" << std::endl;
00126                 continue;
00127             }
00128             if (str[0] == '#') {
00129                 // std::cerr << "[RobotHardware] : loadGain : skip # started line" << std::endl;
00130                 continue;
00131             }
00132             double tmp;
00133             std::istringstream sstrm(str);
00134             sstrm >> tmp;
00135             default_pgain[i] = tmp;
00136             if(sstrm.eof()) break;
00137 
00138             sstrm >> tmp; // I gain
00139             if(sstrm.eof()) break;
00140 
00141             sstrm >> tmp;
00142             default_dgain[i] = tmp;
00143             if(sstrm.eof()) break;
00144 
00145             sstrm >> tmp;
00146             default_tqpgain[i] = tmp;
00147             if(sstrm.eof()) break;
00148 
00149             sstrm >> tmp; // I gain for torque
00150             if(sstrm.eof()) break;
00151 
00152             sstrm >> tmp;
00153             default_tqdgain[i] = tmp;
00154 
00155             break;
00156         }
00157         if(!getlinep) {
00158             if (i < numJoints()) {
00159                 std::cerr << "[RobotHardware] loadGain error: size of gains reading from file ("
00160                           << m_pdgainsFilename
00161                           << ") does not match size of joints" << std::endl;
00162             }
00163             break;
00164         }
00165     }
00166 
00167     strm.close();
00168     // Print loaded gain
00169     std::cerr << "[RobotHardware] loadGain" << std::endl;
00170     for (unsigned int i=0; i<numJoints(); i++) {
00171         std::cerr << "[RobotHardware]   " << joint(i)->name
00172                   << ", pgain = " << default_pgain[i]
00173                   << ", dgain = " << default_dgain[i]
00174                   << ", tqpgain = " << default_tqpgain[i]
00175                   << ", tqdgain = " << default_tqdgain[i]
00176                   << std::endl;
00177     }
00178     return true;
00179 }
00180 
00181 void robot::startInertiaSensorCalibration()
00182 {
00183     std::cerr << "[RobotHardware] startInertiaSensorCalibration..." << std::endl;
00184     if (numSensors(Sensor::ACCELERATION)==0 
00185         && numSensors(Sensor::RATE_GYRO)==0)  return;
00186 
00187     if (isBusy()) return;
00188 
00189     for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
00190         for (int i=0; i<3; i++) {
00191             gyro_sum[j][i] = 0;
00192         }
00193         write_gyro_sensor_offset(j, gyro_sum[j].data());
00194     }
00195 
00196     for(unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
00197         for (int i=0; i<3; i++) {
00198             accel_sum[j][i] = 0;
00199         }
00200         write_accelerometer_offset(j, accel_sum[j].data());
00201     }
00202 
00203 #if 0
00204     for(unsigned int j=0; j<m_natt; j++) {
00205         for (int i=0; i<3; i++) {
00206             att_sum[j][i] = 0;
00207         }
00208         write_attitude_sensor_offset(j, att_sum[j]);
00209     }
00210 #endif
00211 
00212     inertia_calib_counter=CALIB_COUNT;
00213 
00214     sem_wait(&wait_sem);
00215     std::cerr << "[RobotHardware] startInertiaSensorCalibration...done." << std::endl;
00216 }
00217 
00218 void robot::startForceSensorCalibration()
00219 {
00220     if (numSensors(Sensor::FORCE)==0)  return;
00221 
00222     if (isBusy()) return;
00223 
00224     for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
00225         for (int i=0; i<6; i++) {
00226             force_sum[j][i] = 0;
00227         }
00228     }
00229 
00230     force_calib_counter=CALIB_COUNT;
00231 
00232     sem_wait(&wait_sem);
00233 }
00234 
00235 void robot::initializeJointAngle(const char *name, const char *option)
00236 {
00237     m_calibJointName = name;
00238     m_calibOptions   = option;
00239     m_calibRequested = true;
00240     sem_wait(&wait_sem);
00241 }
00242 
00243 void robot::calibrateInertiaSensorOneStep()
00244 {
00245     if (inertia_calib_counter>0) {
00246         for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++){
00247             double rate[3];
00248             read_gyro_sensor(j, rate);
00249             for (int i=0; i<3; i++)
00250                 gyro_sum[j][i] += rate[i];
00251         }
00252         
00253         for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++){
00254             double acc[3];
00255             read_accelerometer(j, acc);
00256             for (int i=0; i<3; i++)
00257                 accel_sum[j][i] += acc[i];
00258         }
00259 
00260 #if 0
00261         for (unsigned int j=0; j<m_natt; j++){
00262             double att[3];
00263             read_attitude_sensor(j, att);
00264             for (int i=0; i<3; i++)
00265                 att_sum[j][i] += att[i];
00266         }
00267 #endif
00268 
00269         inertia_calib_counter--;
00270         if (inertia_calib_counter==0) {
00271 
00272             for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
00273                 for (int i=0; i<3; i++) {
00274                     gyro_sum[j][i] = -gyro_sum[j][i]/CALIB_COUNT;
00275                 }
00276                 write_gyro_sensor_offset(j,  gyro_sum[j].data());
00277             }
00278 
00279             for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
00280                 hrp::Sensor* m_sensor = sensor(hrp::Sensor::ACCELERATION, j);
00281                 hrp::Matrix33 m_sensorR = m_sensor->link->R * m_sensor->localR;
00282                 hrp::Vector3 G_rotated = m_sensorR.transpose() * G;
00283                 for (int i=0; i<3; i++) {
00284                     accel_sum[j][i] = -accel_sum[j][i]/CALIB_COUNT + G_rotated(i);
00285                 }
00286                 write_accelerometer_offset(j, accel_sum[j].data());
00287             }
00288 
00289 #if 0
00290             for (unsigned int j=0; j<m_natt; j++) {
00291                 for (int i=0; i<3; i++) {
00292                     att_sum[j][i] = -att_sum[j][i]/CALIB_COUNT;
00293                 }
00294                 write_attitude_sensor_offset(j, att_sum[j]);
00295             }
00296 #endif
00297 
00298             sem_post(&wait_sem);
00299         }
00300     }
00301 }
00302 
00303 void robot::calibrateForceSensorOneStep()
00304 {
00305     if (force_calib_counter>0) {
00306         for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++){
00307             double force[6];
00308             read_force_sensor(j, force);
00309             for (int i=0; i<6; i++)
00310                 force_sum[j][i] += force[i];
00311         }
00312         force_calib_counter--;
00313         if (force_calib_counter==0) {
00314 
00315             for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
00316                 for (int i=0; i<6; i++) {
00317                     force_sum[j][i] = -force_sum[j][i]/CALIB_COUNT;
00318                 }
00319                 write_force_offset(j,  force_sum[j].data());
00320             }
00321 
00322             sem_post(&wait_sem);
00323         }
00324     }
00325 }
00326 
00327 void robot::gain_control(int i)
00328 {
00329     double new_pgain=0,new_dgain=0,new_tqpgain=0,new_tqdgain=0;
00330     if (gain_counter[i] < GAIN_COUNT){
00331         gain_counter[i]++;
00332         new_pgain = (pgain[i]-old_pgain[i])*gain_counter[i]/GAIN_COUNT + old_pgain[i];
00333         new_dgain = (dgain[i]-old_dgain[i])*gain_counter[i]/GAIN_COUNT + old_dgain[i];
00334         new_tqpgain = (tqpgain[i]-old_tqpgain[i])*gain_counter[i]/GAIN_COUNT + old_tqpgain[i];
00335         new_tqdgain = (tqdgain[i]-old_tqdgain[i])*gain_counter[i]/GAIN_COUNT + old_tqdgain[i];
00336         write_pgain(i, new_pgain);
00337         write_dgain(i, new_dgain);
00338 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00339         write_torque_pgain(i, new_tqpgain);
00340         write_torque_dgain(i, new_tqdgain);
00341 #endif
00342     }
00343 }
00344 
00345 void robot::gain_control()
00346 {
00347     int i;
00348     for (unsigned i=0; i<numJoints(); i++) gain_control(i);
00349 }
00350 
00351 void robot::oneStep()
00352 {
00353     calibrateInertiaSensorOneStep();
00354     calibrateForceSensorOneStep();
00355     gain_control();
00356     if (m_calibRequested){
00357         ::initializeJointAngle(m_calibJointName.c_str(), 
00358                                m_calibOptions.c_str());
00359         m_calibRequested = false;
00360         sem_post(&wait_sem);
00361     }
00362 }
00363 
00364 bool robot::servo(const char *jname, bool turnon)
00365 {
00366     Link *l = NULL;
00367     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00368         bool ret = true;
00369         for (unsigned int i=0; i<numJoints(); i++){
00370             ret = ret && servo(i, turnon);
00371             if (turnon) usleep(m_servoOnDelay*1e6);
00372         }
00373         m_reportedEmergency = false;
00374         return ret;
00375     }else if ((l = link(jname))){
00376         return servo(l->jointId, turnon);
00377     }else{
00378         char *s = (char *)jname; while(*s) {*s=toupper(*s);s++;}
00379         const std::vector<int> jgroup = m_jointGroups[jname];
00380         if (jgroup.size() == 0) return false;
00381         bool ret = true;
00382         for (unsigned int i=0; i<jgroup.size(); i++){
00383             ret = ret && servo(jgroup[i], turnon);
00384             return ret;
00385         }
00386     }
00387     return false;
00388 }
00389 
00390 bool robot::servo(int jid, bool turnon)
00391 {
00392     if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
00393     
00394     int com = OFF;
00395 
00396     if (turnon) {
00397         com = ON;
00398     }
00399 
00400     write_pgain(jid, 0);
00401     write_dgain(jid, 0);
00402     old_pgain[jid] = 0;
00403     old_dgain[jid] = 0;
00404 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00405     write_torque_pgain(jid, 0);
00406     write_torque_dgain(jid, 0);
00407 #endif
00408     old_tqpgain[jid] = 0;
00409     old_tqdgain[jid] = 0;
00410     if (turnon){
00411         double angle;
00412         read_actual_angle(jid, &angle);
00413             write_command_angle(jid, angle);
00414     }
00415     write_servo(jid, com);
00416     if (turnon) gain_counter[jid] = 0;
00417 
00418     return true;
00419 }
00420 
00421 
00422 bool robot::power(const char *jname, bool turnon)
00423 {
00424     int jid = JID_INVALID;
00425 
00426     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00427         jid = JID_ALL;
00428     }else{
00429         Link *l = link(jname);
00430         if (!l) return false;
00431         jid = l->jointId;
00432     }
00433     return power(jid, turnon);
00434 }
00435 
00436 bool robot::power(int jid, bool turnon)
00437 {
00438     if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
00439   
00440     int com = OFF;
00441 
00442     if (turnon) {
00443         for(unsigned int i=0; i<numJoints(); i++) {
00444             int s;
00445             read_servo_state(i, &s);
00446             if (s == ON)
00447                 return false;
00448         }
00449         com = ON;
00450     }
00451 
00452     // next part written as if there is a relay for each joint
00453     // up to HRP2, TREX, PARASA there is only one.
00454 
00455     if(jid == JID_ALL) {
00456         if (com == OFF) {
00457             for (unsigned int i=0; i<numJoints(); i++) {
00458                 write_pgain(i, 0);
00459                 write_dgain(i, 0);
00460 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00461                 write_torque_pgain(i, 0);
00462                 write_torque_dgain(i, 0);
00463 #endif
00464                 write_servo(i, com);
00465                 write_power_command(i, com);
00466             }
00467         } else       
00468             for (unsigned int i=0; i<numJoints(); i++)
00469                 write_power_command(i, com);
00470     } else {
00471         if (com == OFF) {
00472             write_pgain(jid, 0);
00473             write_dgain(jid, 0);
00474 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00475             write_torque_pgain(jid, 0);
00476             write_torque_dgain(jid, 0);
00477 #endif
00478             write_servo(jid, com);
00479             write_power_command(jid, com);
00480         } else {
00481             write_power_command(jid, com);
00482         }
00483     }
00484 
00485     return true;
00486 }
00487 
00488 bool robot::isBusy() const
00489 {
00490     if (inertia_calib_counter > 0 || force_calib_counter > 0)
00491         return true;
00492 
00493     for (unsigned int i=0; i<numJoints(); i++) {
00494         if (gain_counter[i] < GAIN_COUNT) {
00495             return true;
00496         }
00497     }
00498 
00499     return false; 
00500 }
00501 
00502 void robot::readJointAngles(double *o_angles)
00503 {
00504     read_actual_angles(o_angles);
00505 }
00506 
00507 void robot::readJointVelocities(double *o_velocities)
00508 {
00509     read_actual_velocities(o_velocities);
00510 }
00511 
00512 int robot::readJointTorques(double *o_torques)
00513 {
00514     return read_actual_torques(o_torques);
00515 }
00516 
00517 int robot::readJointCommandTorques(double *o_torques)
00518 {
00519     return read_command_torques(o_torques);
00520 }
00521 
00522 void robot::readGyroSensor(unsigned int i_rank, double *o_rates)
00523 {
00524     read_gyro_sensor(i_rank, o_rates);
00525 }
00526 
00527 void robot::readAccelerometer(unsigned int i_rank, double *o_accs)
00528 {
00529     read_accelerometer(i_rank, o_accs);
00530 }
00531 
00532 void robot::readForceSensor(unsigned int i_rank, double *o_forces)
00533 {
00534     read_force_sensor(i_rank, o_forces);
00535 }
00536 
00537 void robot::writeJointCommands(const double *i_commands)
00538 {
00539     if (!m_commandOld.size()) {
00540         m_commandOld.resize(numJoints());
00541         m_velocityOld.resize(numJoints());
00542     }
00543     for (unsigned int i=0; i<numJoints(); i++){
00544         m_velocityOld[i] = (i_commands[i] - m_commandOld[i])/m_dt;
00545         m_commandOld[i] = i_commands[i];
00546     }
00547     write_command_angles(i_commands);
00548 }
00549 
00550 void robot::readJointCommands(double *o_commands)
00551 {
00552     read_command_angles(o_commands);
00553 }
00554 
00555 void robot::writeTorqueCommands(const double *i_commands)
00556 {
00557     write_command_torques(i_commands);
00558 }
00559 
00560 void robot::writeVelocityCommands(const double *i_commands)
00561 {
00562     write_command_velocities(i_commands);
00563 }
00564 
00565 void robot::writeAccelerationCommands(const double *i_commands)
00566 {
00567 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
00568     write_command_accelerations(i_commands);
00569 #endif
00570 }
00571 
00572 void robot::readPowerStatus(double &o_voltage, double &o_current)
00573 {
00574     read_power(&o_voltage, &o_current);
00575 }
00576 
00577 int robot::readCalibState(int i)
00578 {
00579     int v=0;
00580     read_calib_state(i, &v);
00581     return v;
00582 }
00583 
00584 int robot::readPowerState(int i)
00585 {
00586     int v=0;
00587     read_power_state(i, &v);
00588     return v;
00589 }
00590 
00591 int robot::readServoState(int i)
00592 {
00593     int v=0;
00594     read_servo_state(i, &v);
00595     return v;
00596 }
00597 
00598 int robot::readServoAlarm(int i)
00599 {
00600     int v=0;
00601     read_servo_alarm(i, &v);
00602     return v;
00603 }
00604 
00605 int robot::readDriverTemperature(int i)
00606 {
00607     unsigned char temp=0;
00608     read_driver_temperature(i, &temp);
00609     return temp;
00610 }
00611 
00612 char *time_string()
00613 {
00614     struct timeval tv;
00615     gettimeofday(&tv, NULL);
00616     struct tm *tm_ = localtime(&tv.tv_sec);
00617     static char time[20];
00618     sprintf(time, "%02d:%02d:%02d.%06d", tm_->tm_hour, tm_->tm_min, tm_->tm_sec, (int)tv.tv_usec);
00619     return time;
00620 }
00621 
00622 bool robot::checkJointCommands(const double *i_commands)
00623 {
00624     if (!m_dt) return false;
00625     if (!m_commandOld.size()) return false;
00626 
00627     int state;
00628     for (unsigned int i=0; i<numJoints(); i++){
00629         read_servo_state(i, &state);
00630         if (state == ON){
00631             double command_old=m_commandOld[i], command=i_commands[i];
00632             double v = (command - command_old)/m_dt;
00633             if (fabs(v) > joint(i)->uvlimit){
00634                 std::cerr << time_string()
00635                           << ": joint command velocity limit over: joint = " 
00636                           << joint(i)->name
00637                           << ", vlimit = " << joint(i)->uvlimit/M_PI*180 
00638                           << "[deg/s], v = " 
00639                           << v/M_PI*180 << "[deg/s]" << std::endl;
00640                 return true;
00641             }
00642             double a = (v - m_velocityOld[i])/m_dt;
00643             if (m_accLimit && fabs(a) > m_accLimit){
00644                 std::cerr << time_string()
00645                           << ": joint command acceleration limit over: joint = " 
00646                           << joint(i)->name
00647                           << ", alimit = " << m_accLimit/M_PI*180 
00648                           << "[deg/s^2], v = " 
00649                           << a/M_PI*180 << "[deg/s^2]" << std::endl;
00650                 return true;
00651             }
00652         }
00653     }
00654     return false;
00655 }
00656 
00657 bool robot::checkEmergency(emg_reason &o_reason, int &o_id)
00658 {
00659     int state;
00660     for (unsigned int i=0; i<numJoints(); i++){
00661         read_servo_state(i, &state);
00662         if (state == ON && m_servoErrorLimit[i] != 0){
00663             double angle, command;
00664             read_actual_angle(i, &angle);
00665             read_command_angle(i, &command);
00666             if (fabs(angle-command) > m_servoErrorLimit[i]){
00667                 std::cerr << time_string()
00668                           << ": servo error limit over: joint = " 
00669                           << joint(i)->name
00670                           << ", qRef = " << command/M_PI*180 << "[deg], q = " 
00671                           << angle/M_PI*180 << "[deg]" << std::endl;
00672                 o_reason = EMG_SERVO_ERROR;
00673                 o_id = i;
00674                 return true;
00675             }
00676         }
00677     }
00678 
00679     if (m_rLegForceSensorId >= 0){
00680         double force[6];
00681         read_force_sensor(m_rLegForceSensorId, force);
00682         if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
00683             std::cerr << time_string() << ": right Fz limit over: Fz = " << force[FZ] << std::endl;
00684             o_reason = EMG_FZ;
00685             o_id = m_rLegForceSensorId;
00686             return true;
00687         }
00688     } 
00689     if (m_lLegForceSensorId >= 0){
00690         double force[6];
00691         read_force_sensor(m_lLegForceSensorId, force);
00692         if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
00693             std::cerr << time_string() << ": left Fz limit over: Fz = " << force[FZ] << std::endl;
00694             o_reason = EMG_FZ;
00695             o_id = m_lLegForceSensorId;
00696             return true;
00697         }
00698     } 
00699     int alarm;
00700     for (unsigned int i=0; i<numJoints(); i++){
00701         if (!read_servo_alarm(i, &alarm)) continue;
00702         if (alarm & SS_EMERGENCY) {
00703             if (!m_reportedEmergency) {
00704                 m_reportedEmergency = true;
00705                 o_reason = EMG_SERVO_ALARM;
00706                 o_id = i;
00707             }
00708             return true;
00709         }
00710     }
00711     m_reportedEmergency = false;
00712     // Power state check
00713     if (m_enable_poweroff_check) {
00714       int pstate, sstate;
00715       for (unsigned int i=0; i<numJoints(); i++){
00716         read_power_state(i, &pstate);
00717         read_servo_state(i, &sstate);
00718         // If power OFF while servo ON
00719         if (!m_reportedEmergency && (pstate == OFF) && (sstate == ON) ) {
00720           m_reportedEmergency = true;
00721           o_reason = EMG_POWER_OFF;
00722           o_id = i;
00723           std::cerr << time_string() << ": power off detected : joint = " << joint(i)->name << std::endl;
00724           return true;
00725         }
00726       }
00727       m_reportedEmergency = false;
00728     }
00729     return false;
00730 }
00731 
00732 bool robot::setServoGainPercentage(const char *i_jname, double i_percentage)
00733 {
00734     if ( i_percentage < 0 || 100 < i_percentage ) {
00735         std::cerr << "[RobotHardware] Invalid percentage " <<  i_percentage << "[%] for setServoGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
00736         return false;
00737     }
00738     Link *l = NULL;
00739     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00740         for (unsigned int i=0; i<numJoints(); i++){
00741             if (!read_pgain(i, &old_pgain[i])) old_pgain[i] = pgain[i];
00742             pgain[i] = default_pgain[i] * i_percentage/100.0;
00743             if (!read_dgain(i, &old_dgain[i])) old_dgain[i] = dgain[i];
00744             dgain[i] = default_dgain[i] * i_percentage/100.0;
00745 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00746             if (!read_torque_pgain(i, &old_tqpgain[i])) old_tqpgain[i] = tqpgain[i];
00747             if (!read_torque_dgain(i, &old_tqdgain[i])) old_tqdgain[i] = tqdgain[i];
00748 #endif
00749             gain_counter[i] = 0;
00750         }
00751         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for all joints" << std::endl;
00752     }else if ((l = link(i_jname))){
00753         if (!read_pgain(l->jointId, &old_pgain[l->jointId])) old_pgain[l->jointId] = pgain[l->jointId];
00754         pgain[l->jointId] = default_pgain[l->jointId] * i_percentage/100.0;
00755         if (!read_dgain(l->jointId, &old_dgain[l->jointId])) old_dgain[l->jointId] = dgain[l->jointId];
00756         dgain[l->jointId] = default_dgain[l->jointId] * i_percentage/100.0;
00757 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00758         if (!read_torque_pgain(l->jointId, &old_tqpgain[l->jointId])) old_tqpgain[l->jointId] = tqpgain[l->jointId];
00759         if (!read_torque_dgain(l->jointId, &old_tqdgain[l->jointId])) old_tqdgain[l->jointId] = tqdgain[l->jointId];
00760 #endif
00761         gain_counter[l->jointId] = 0;
00762         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00763     }else{
00764         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00765         const std::vector<int> jgroup = m_jointGroups[i_jname];
00766         if (jgroup.size()==0) return false;
00767         for (unsigned int i=0; i<jgroup.size(); i++){
00768             if (!read_pgain(jgroup[i], &old_pgain[jgroup[i]])) old_pgain[jgroup[i]] = pgain[jgroup[i]];
00769             pgain[jgroup[i]] = default_pgain[jgroup[i]] * i_percentage/100.0;
00770             if (!read_dgain(jgroup[i], &old_dgain[jgroup[i]])) old_dgain[jgroup[i]] = dgain[jgroup[i]];
00771             dgain[jgroup[i]] = default_dgain[jgroup[i]] * i_percentage/100.0;
00772 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00773             if (!read_torque_pgain(jgroup[i], &old_tqpgain[jgroup[i]])) old_tqpgain[jgroup[i]] = tqpgain[jgroup[i]];
00774             if (!read_torque_dgain(jgroup[i], &old_tqdgain[jgroup[i]])) old_tqdgain[jgroup[i]] = tqdgain[jgroup[i]];
00775 #endif
00776             gain_counter[jgroup[i]] = 0;
00777         }
00778         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00779     }
00780     return true;
00781 }
00782 
00783 bool robot::setServoTorqueGainPercentage(const char *i_jname, double i_percentage)
00784 {
00785     if ( i_percentage < 0 && 100 < i_percentage ) {
00786         std::cerr << "[RobotHardware] Invalid percentage " <<  i_percentage << "[%] for setServoTorqueGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
00787         return false;
00788     }
00789     Link *l = NULL;
00790     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00791         for (int i=0; i<numJoints(); i++){
00792 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00793             if (!read_torque_pgain(i, &old_tqpgain[i])) old_tqpgain[i] = tqpgain[i];
00794             tqpgain[i] = default_tqpgain[i] * i_percentage/100.0;
00795             if (!read_torque_dgain(i, &old_tqdgain[i])) old_tqdgain[i] = tqdgain[i];
00796             tqdgain[i] = default_tqdgain[i] * i_percentage/100.0;
00797 #endif
00798             if (!read_pgain(i, &old_pgain[i])) old_pgain[i] = pgain[i];
00799             if (!read_dgain(i, &old_dgain[i])) old_dgain[i] = dgain[i];
00800             gain_counter[i] = 0;
00801         }
00802         std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for all joints" << std::endl;
00803     }else if ((l = link(i_jname))){
00804 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00805         if (!read_torque_pgain(l->jointId, &old_tqpgain[l->jointId])) old_tqpgain[l->jointId] = tqpgain[l->jointId];
00806         tqpgain[l->jointId] = default_tqpgain[l->jointId] * i_percentage/100.0;
00807         if (!read_torque_dgain(l->jointId, &old_tqdgain[l->jointId])) old_tqdgain[l->jointId] = tqdgain[l->jointId];
00808         tqdgain[l->jointId] = default_tqdgain[l->jointId] * i_percentage/100.0;
00809 #endif
00810         if (!read_pgain(l->jointId, &old_pgain[l->jointId])) old_pgain[l->jointId] = pgain[l->jointId];
00811         if (!read_dgain(l->jointId, &old_dgain[l->jointId])) old_dgain[l->jointId] = dgain[l->jointId];
00812         gain_counter[l->jointId] = 0;
00813         std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00814     }else{
00815         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00816         const std::vector<int> jgroup = m_jointGroups[i_jname];
00817         if (jgroup.size()==0) return false;
00818         for (unsigned int i=0; i<jgroup.size(); i++){
00819 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00820             if (!read_torque_pgain(jgroup[i], &old_tqpgain[jgroup[i]])) old_tqpgain[jgroup[i]] = tqpgain[jgroup[i]];
00821             tqpgain[jgroup[i]] = default_tqpgain[jgroup[i]] * i_percentage/100.0;
00822             if (!read_torque_dgain(jgroup[i], &old_tqdgain[jgroup[i]])) old_tqdgain[jgroup[i]] = tqdgain[jgroup[i]];
00823             tqdgain[jgroup[i]] = default_tqdgain[jgroup[i]] * i_percentage/100.0;
00824 #endif
00825             if (!read_pgain(jgroup[i], &old_pgain[jgroup[i]])) old_pgain[jgroup[i]] = pgain[jgroup[i]];
00826             if (!read_dgain(jgroup[i], &old_dgain[jgroup[i]])) old_dgain[jgroup[i]] = dgain[jgroup[i]];
00827             gain_counter[jgroup[i]] = 0;
00828         }
00829         std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00830     }
00831     return true;
00832 }
00833 
00834 bool robot::setServoErrorLimit(const char *i_jname, double i_limit)
00835 {
00836     Link *l = NULL;
00837     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00838         for (unsigned int i=0; i<numJoints(); i++){
00839             m_servoErrorLimit[i] = i_limit;
00840         }
00841     }else if ((l = link(i_jname))){
00842         m_servoErrorLimit[l->jointId] = i_limit;
00843     }else{
00844         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00845         const std::vector<int> jgroup = m_jointGroups[i_jname];
00846         if (jgroup.size()==0) return false;
00847         for (unsigned int i=0; i<jgroup.size(); i++){
00848             m_servoErrorLimit[jgroup[i]] = i_limit;
00849         }
00850     }
00851     return true;
00852 }
00853 
00854 void robot::setProperty(const char *i_key, const char *i_value)
00855 {
00856     std::istringstream iss(i_value);
00857     std::string key(i_key);
00858     bool isKnownKey = true;
00859     if (key == "sensor_id.right_leg_force_sensor"){
00860         iss >> m_rLegForceSensorId;
00861     }else if (key == "sensor_id.left_leg_force_sensor"){
00862         iss >> m_lLegForceSensorId;
00863     }else if (key == "pdgains.file_name"){
00864         iss >> m_pdgainsFilename;
00865     }else if (key == "enable_poweroff_check"){
00866         std::string tmp;
00867         iss >> tmp;
00868         m_enable_poweroff_check = (tmp=="true");
00869     }else{
00870         isKnownKey = false;
00871     }
00872     if (isKnownKey) std::cout << i_key << ": " << i_value << std::endl;
00873 }
00874 
00875 bool robot::names2ids(const std::vector<std::string> &i_names, 
00876                             std::vector<int> &o_ids)
00877 { 
00878     bool ret = true;
00879     for (unsigned int i=0; i<i_names.size(); i++){
00880         Link *l = link(i_names[i].c_str());
00881         if (!l){
00882             std::cout << "joint named [" << i_names[i] << "] not found" 
00883                       << std::endl;
00884             ret = false;
00885         }else{
00886             o_ids.push_back(l->jointId);
00887         }
00888     }
00889     return ret;
00890 }
00891 
00892 bool robot::addJointGroup(const char *gname, const std::vector<std::string>& jnames)
00893 {
00894     char *s = (char *)gname; while(*s) {*s=toupper(*s);s++;}
00895     std::vector<int> jids;
00896     bool ret = names2ids(jnames, jids);
00897     m_jointGroups[gname] = jids;
00898     return ret;
00899 }
00900 
00901 size_t robot::lengthOfExtraServoState(int id)
00902 {
00903     return length_of_extra_servo_state(id);
00904 }
00905 
00906 void robot::readExtraServoState(int id, int *state)
00907 {
00908     read_extra_servo_state(id, state);
00909 }
00910 
00911 bool robot::readDigitalInput(char *o_din)
00912 {
00913 #ifndef NO_DIGITAL_INPUT
00914     return read_digital_input(o_din);
00915 #else
00916     return false;
00917 #endif
00918 }
00919 
00920 int robot::lengthDigitalInput()
00921 {
00922 #ifndef NO_DIGITAL_INPUT
00923     return length_digital_input();
00924 #else
00925     return 0;
00926 #endif
00927 }
00928 
00929 bool robot::writeDigitalOutput(const char *i_dout)
00930 {
00931     return write_digital_output(i_dout);
00932 }
00933 
00934 bool robot::writeDigitalOutputWithMask(const char *i_dout, const char *i_mask)
00935 {
00936     return write_digital_output_with_mask(i_dout, i_mask);
00937 }
00938 
00939 int robot::lengthDigitalOutput()
00940 {
00941     return length_digital_output();
00942 }
00943 
00944 bool robot::readDigitalOutput(char *o_dout)
00945 {
00946     return read_digital_output(o_dout);
00947 }
00948 
00949 void robot::readBatteryState(unsigned int i_rank, double &voltage, 
00950                              double &current, double &soc)
00951 {
00952 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00953     read_battery(i_rank, &voltage, &current, &soc);
00954 #else
00955     voltage=0; current=0; soc=0;
00956 #endif
00957 }
00958 
00959 int robot::numBatteries()
00960 {
00961 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00962     return number_of_batteries();
00963 #else
00964     return 0;
00965 #endif
00966 }
00967 
00968 void robot::readThermometer(unsigned int i_rank, double &o_temp)
00969 {
00970 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00971     read_temperature(i_rank, &o_temp);
00972 #else
00973     o_temp=0;
00974 #endif
00975 }
00976 
00977 int robot::numThermometers()
00978 {
00979 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00980     return number_of_thermometers();
00981 #else
00982     return 0;
00983 #endif
00984 }
00985 
00986 bool robot::setJointInertia(const char *jname, double mn)
00987 {
00988 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
00989     Link *l = link(jname);
00990     if (!l) return false;
00991     int jid = l->jointId;
00992     return write_joint_inertia(jid, mn);
00993 #else
00994     return false;
00995 #endif
00996 }
00997 
00998 void robot::setJointInertias(const double *mns)
00999 {
01000 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
01001     write_joint_inertias(mns);
01002 #endif
01003 }
01004 
01005 int robot::readPDControllerTorques(double *o_torques)
01006 {
01007 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
01008     return read_pd_controller_torques(o_torques);
01009 #else
01010     return 0;
01011 #endif
01012 }
01013 
01014 void robot::enableDisturbanceObserver()
01015 {
01016 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
01017     write_disturbance_observer(ON);
01018 #endif
01019 }
01020 
01021 void robot::disableDisturbanceObserver()
01022 {
01023 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
01024     write_disturbance_observer(OFF);
01025 #endif
01026 }
01027 
01028 void robot::setDisturbanceObserverGain(double gain)
01029 {
01030 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
01031     write_disturbance_observer_gain(gain);
01032 #endif
01033 }
01034 
01035 bool robot::setJointControlMode(const char *i_jname, joint_control_mode mode)
01036 {
01037     Link *l = NULL;
01038     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0) {
01039         for (int i=0; i < numJoints(); i++) {
01040             write_control_mode(i, mode);
01041         }
01042         std::cerr << "[RobotHardware] setJointControlMode for all joints : " << mode << std::endl;
01043     } else if ((l = link(i_jname))) {
01044         write_control_mode(l->jointId, mode);
01045         std::cerr << "[RobotHardware] setJointControlMode for " << i_jname << " : " << mode << std::endl;
01046     } else {
01047         char *s = (char *)i_jname; while(*s) { *s=toupper(*s); s++; }
01048         const std::vector<int> jgroup = m_jointGroups[i_jname];
01049         if (jgroup.size()==0) return false;
01050         for (unsigned int i=0; i<jgroup.size(); i++) {
01051             write_control_mode(jgroup[i], mode);
01052         }
01053         std::cerr << "[RobotHardware] setJointControlMode for " << i_jname << " : " << mode << std::endl;
01054     }
01055     return true;
01056 }


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:18