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)
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     for (unsigned int i=0; i<numJoints(); i++){
00050         pgain[i] = dgain[i] = 0.0;
00051         old_pgain[i] = old_dgain[i] = 0.0;
00052         default_pgain[i] = default_dgain[i] = 0.0;
00053     } 
00054     loadGain();
00055     for (unsigned int i=0; i<numJoints(); i++){
00056         pgain[i] = default_pgain[i];
00057         dgain[i] = default_dgain[i];
00058     }
00059 
00060     m_servoErrorLimit.resize(numJoints());
00061     for (unsigned int i=0; i<numJoints(); i++){
00062         m_servoErrorLimit[i] = DEFAULT_ANGLE_ERROR_LIMIT;
00063     }
00064 
00065 
00066 
00067     set_number_of_joints(numJoints());
00068     set_number_of_force_sensors(numSensors(Sensor::FORCE));
00069     set_number_of_gyro_sensors(numSensors(Sensor::RATE_GYRO));
00070     set_number_of_accelerometers(numSensors(Sensor::ACCELERATION));
00071 
00072     gyro_sum.resize(numSensors(Sensor::RATE_GYRO));
00073     accel_sum.resize(numSensors(Sensor::ACCELERATION));
00074     force_sum.resize(numSensors(Sensor::FORCE));
00075 
00076     if ((number_of_joints() != (int)numJoints())
00077         || (number_of_force_sensors() != (int)numSensors(Sensor::FORCE))
00078         || (number_of_gyro_sensors() != (int)numSensors(Sensor::RATE_GYRO))
00079         || (number_of_accelerometers() != (int)numSensors(Sensor::ACCELERATION))){
00080       std::cerr << "VRML and IOB are inconsistent" << std::endl;
00081       std::cerr << "  joints:" << numJoints() << "(VRML), " << number_of_joints() << "(IOB)"  << std::endl;
00082       std::cerr << "  force sensor:" << numSensors(Sensor::FORCE) << "(VRML), " << number_of_force_sensors() << "(IOB)"  << std::endl;
00083       std::cerr << "  gyro sensor:" << numSensors(Sensor::RATE_GYRO) << "(VRML), " << number_of_gyro_sensors() << "(IOB)"  << std::endl;
00084       std::cerr << "  accelerometer:" << numSensors(Sensor::ACCELERATION) << "(VRML), " << number_of_accelerometers() << "(IOB)"  << std::endl;
00085       return false;
00086     }
00087     G << 0, 0, 9.8;
00088 
00089     if (open_iob() == FALSE) return false;
00090 
00091     return true;
00092 }
00093 
00094 void robot::removeForceSensorOffset()
00095 {
00096     std::cerr << "[RobotHardware] removeForceSensorOffset..." << std::endl;
00097     startForceSensorCalibration();
00098     std::cerr << "[RobotHardware] removeForceSensorOffset...done." << std::endl;
00099 }
00100 
00101 bool robot::loadGain()
00102 {
00103     std::ifstream strm(m_pdgainsFilename.c_str());
00104     if (!strm.is_open()) {
00105         std::cerr << m_pdgainsFilename << " not found" << std::endl;
00106         return false;
00107     }
00108 
00109     double dummy;
00110     for (unsigned int i=0; i<numJoints(); i++){
00111         strm >> default_pgain[i];
00112         strm >> dummy;
00113         strm >> default_dgain[i];
00114     }
00115     strm.close();
00116     // Print loaded gain
00117     std::cerr << "[RobotHardware] loadGain" << std::endl;
00118     for (unsigned int i=0; i<numJoints(); i++) {                                                                                                                                               std::cerr << "[RobotHardware]   " << joint(i)->name << ", pgain = " << default_pgain[i] << ", dgain = " << default_dgain[i] << std::endl;
00119     }
00120     return true;
00121 }
00122 
00123 void robot::startInertiaSensorCalibration()
00124 {
00125     std::cerr << "[RobotHardware] startInertiaSensorCalibration..." << std::endl;
00126     if (numSensors(Sensor::ACCELERATION)==0 
00127         && numSensors(Sensor::RATE_GYRO)==0)  return;
00128 
00129     if (isBusy()) return;
00130 
00131     for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
00132         for (int i=0; i<3; i++) {
00133             gyro_sum[j][i] = 0;
00134         }
00135         write_gyro_sensor_offset(j, gyro_sum[j].data());
00136     }
00137 
00138     for(unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
00139         for (int i=0; i<3; i++) {
00140             accel_sum[j][i] = 0;
00141         }
00142         write_accelerometer_offset(j, accel_sum[j].data());
00143     }
00144 
00145 #if 0
00146     for(unsigned int j=0; j<m_natt; j++) {
00147         for (int i=0; i<3; i++) {
00148             att_sum[j][i] = 0;
00149         }
00150         write_attitude_sensor_offset(j, att_sum[j]);
00151     }
00152 #endif
00153 
00154     inertia_calib_counter=CALIB_COUNT;
00155 
00156     sem_wait(&wait_sem);
00157     std::cerr << "[RobotHardware] startInertiaSensorCalibration...done." << std::endl;
00158 }
00159 
00160 void robot::startForceSensorCalibration()
00161 {
00162     if (numSensors(Sensor::FORCE)==0)  return;
00163 
00164     if (isBusy()) return;
00165 
00166     for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
00167         for (int i=0; i<6; i++) {
00168             force_sum[j][i] = 0;
00169         }
00170     }
00171 
00172     force_calib_counter=CALIB_COUNT;
00173 
00174     sem_wait(&wait_sem);
00175 }
00176 
00177 void robot::initializeJointAngle(const char *name, const char *option)
00178 {
00179     m_calibJointName = name;
00180     m_calibOptions   = option;
00181     m_calibRequested = true;
00182     sem_wait(&wait_sem);
00183 }
00184 
00185 void robot::calibrateInertiaSensorOneStep()
00186 {
00187     if (inertia_calib_counter>0) {
00188         for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++){
00189             double rate[3];
00190             read_gyro_sensor(j, rate);
00191             for (int i=0; i<3; i++)
00192                 gyro_sum[j][i] += rate[i];
00193         }
00194         
00195         for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++){
00196             double acc[3];
00197             read_accelerometer(j, acc);
00198             for (int i=0; i<3; i++)
00199                 accel_sum[j][i] += acc[i];
00200         }
00201 
00202 #if 0
00203         for (unsigned int j=0; j<m_natt; j++){
00204             double att[3];
00205             read_attitude_sensor(j, att);
00206             for (int i=0; i<3; i++)
00207                 att_sum[j][i] += att[i];
00208         }
00209 #endif
00210 
00211         inertia_calib_counter--;
00212         if (inertia_calib_counter==0) {
00213 
00214             for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
00215                 for (int i=0; i<3; i++) {
00216                     gyro_sum[j][i] = -gyro_sum[j][i]/CALIB_COUNT;
00217                 }
00218                 write_gyro_sensor_offset(j,  gyro_sum[j].data());
00219             }
00220 
00221             for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
00222                 hrp::Sensor* m_sensor = sensor(hrp::Sensor::ACCELERATION, j);
00223                 hrp::Matrix33 m_sensorR = m_sensor->link->R * m_sensor->localR;
00224                 hrp::Vector3 G_rotated = m_sensorR.transpose() * G;
00225                 for (int i=0; i<3; i++) {
00226                     accel_sum[j][i] = -accel_sum[j][i]/CALIB_COUNT + G_rotated(i);
00227                 }
00228                 write_accelerometer_offset(j, accel_sum[j].data());
00229             }
00230 
00231 #if 0
00232             for (unsigned int j=0; j<m_natt; j++) {
00233                 for (int i=0; i<3; i++) {
00234                     att_sum[j][i] = -att_sum[j][i]/CALIB_COUNT;
00235                 }
00236                 write_attitude_sensor_offset(j, att_sum[j]);
00237             }
00238 #endif
00239 
00240             sem_post(&wait_sem);
00241         }
00242     }
00243 }
00244 
00245 void robot::calibrateForceSensorOneStep()
00246 {
00247     if (force_calib_counter>0) {
00248         for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++){
00249             double force[6];
00250             read_force_sensor(j, force);
00251             for (int i=0; i<6; i++)
00252                 force_sum[j][i] += force[i];
00253         }
00254         force_calib_counter--;
00255         if (force_calib_counter==0) {
00256 
00257             for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
00258                 for (int i=0; i<6; i++) {
00259                     force_sum[j][i] = -force_sum[j][i]/CALIB_COUNT;
00260                 }
00261                 write_force_offset(j,  force_sum[j].data());
00262             }
00263 
00264             sem_post(&wait_sem);
00265         }
00266     }
00267 }
00268 
00269 void robot::gain_control(int i)
00270 {
00271     double new_pgain=0,new_dgain=0;
00272     if (gain_counter[i] < GAIN_COUNT){
00273         gain_counter[i]++;
00274         new_pgain = (pgain[i]-old_pgain[i])*gain_counter[i]/GAIN_COUNT + old_pgain[i];
00275         new_dgain = (dgain[i]-old_dgain[i])*gain_counter[i]/GAIN_COUNT + old_dgain[i];
00276         write_pgain(i, new_pgain);
00277         write_dgain(i, new_dgain);
00278     }
00279 }
00280 
00281 void robot::gain_control()
00282 {
00283     int i;
00284     for (unsigned i=0; i<numJoints(); i++) gain_control(i);
00285 }
00286 
00287 void robot::oneStep()
00288 {
00289     calibrateInertiaSensorOneStep();
00290     calibrateForceSensorOneStep();
00291     gain_control();
00292     if (m_calibRequested){
00293         ::initializeJointAngle(m_calibJointName.c_str(), 
00294                                m_calibOptions.c_str());
00295         m_calibRequested = false;
00296         sem_post(&wait_sem);
00297     }
00298 }
00299 
00300 bool robot::servo(const char *jname, bool turnon)
00301 {
00302     Link *l = NULL;
00303     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00304         bool ret = true;
00305         for (unsigned int i=0; i<numJoints(); i++){
00306             ret = ret && servo(i, turnon);
00307         }
00308         m_reportedEmergency = false;
00309         return ret;
00310     }else if ((l = link(jname))){
00311         return servo(l->jointId, turnon);
00312     }else{
00313         char *s = (char *)jname; while(*s) {*s=toupper(*s);s++;}
00314         const std::vector<int> jgroup = m_jointGroups[jname];
00315         if (jgroup.size() == 0) return false;
00316         bool ret = true;
00317         for (unsigned int i=0; i<jgroup.size(); i++){
00318             ret = ret && servo(jgroup[i], turnon);
00319             return ret;
00320         }
00321     }
00322     return false;
00323 }
00324 
00325 bool robot::servo(int jid, bool turnon)
00326 {
00327     if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
00328     
00329     int com = OFF;
00330 
00331     if (turnon) {
00332         com = ON;
00333     }
00334 
00335     write_pgain(jid, 0);
00336     write_dgain(jid, 0);
00337     old_pgain[jid] = 0;
00338     old_dgain[jid] = 0;
00339     if (turnon){
00340         double angle;
00341         read_actual_angle(jid, &angle);
00342             write_command_angle(jid, angle);
00343     }
00344     write_servo(jid, com);
00345     if (turnon) gain_counter[jid] = 0;
00346 
00347     return true;
00348 }
00349 
00350 
00351 bool robot::power(const char *jname, bool turnon)
00352 {
00353     int jid = JID_INVALID;
00354 
00355     if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
00356         jid = JID_ALL;
00357     }else{
00358         Link *l = link(jname);
00359         if (!l) return false;
00360         jid = l->jointId;
00361     }
00362     return power(jid, turnon);
00363 }
00364 
00365 bool robot::power(int jid, bool turnon)
00366 {
00367     if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
00368   
00369     int com = OFF;
00370 
00371     if (turnon) {
00372         for(unsigned int i=0; i<numJoints(); i++) {
00373             int s;
00374             read_servo_state(i, &s);
00375             if (s == ON)
00376                 return false;
00377         }
00378         com = ON;
00379     }
00380 
00381     // next part written as if there is a relay for each joint
00382     // up to HRP2, TREX, PARASA there is only one.
00383 
00384     if(jid == JID_ALL) {
00385         if (com == OFF) {
00386             for (unsigned int i=0; i<numJoints(); i++) {
00387                 write_pgain(i, 0);
00388                 write_dgain(i, 0);
00389                 write_servo(i, com);
00390                 write_power_command(i, com);
00391             }
00392         } else       
00393             for (unsigned int i=0; i<numJoints(); i++)
00394                 write_power_command(i, com);
00395     } else {
00396         if (com == OFF) {
00397             write_pgain(jid, 0);
00398             write_dgain(jid, 0);
00399             write_servo(jid, com);
00400             write_power_command(jid, com);
00401         } else {
00402             write_power_command(jid, com);
00403         }
00404     }
00405 
00406     return true;
00407 }
00408 
00409 bool robot::isBusy() const
00410 {
00411     if (inertia_calib_counter > 0 || force_calib_counter > 0)
00412         return true;
00413 
00414     for (unsigned int i=0; i<numJoints(); i++) {
00415         if (gain_counter[i] < GAIN_COUNT) {
00416             return true;
00417         }
00418     }
00419 
00420     return false; 
00421 }
00422 
00423 void robot::readJointAngles(double *o_angles)
00424 {
00425     read_actual_angles(o_angles);
00426 }
00427 
00428 void robot::readJointVelocities(double *o_velocities)
00429 {
00430     read_actual_velocities(o_velocities);
00431 }
00432 
00433 int robot::readJointTorques(double *o_torques)
00434 {
00435     return read_actual_torques(o_torques);
00436 }
00437 
00438 int robot::readJointCommandTorques(double *o_torques)
00439 {
00440     return read_command_torques(o_torques);
00441 }
00442 
00443 void robot::readGyroSensor(unsigned int i_rank, double *o_rates)
00444 {
00445     read_gyro_sensor(i_rank, o_rates);
00446 }
00447 
00448 void robot::readAccelerometer(unsigned int i_rank, double *o_accs)
00449 {
00450     read_accelerometer(i_rank, o_accs);
00451 }
00452 
00453 void robot::readForceSensor(unsigned int i_rank, double *o_forces)
00454 {
00455     read_force_sensor(i_rank, o_forces);
00456 }
00457 
00458 void robot::writeJointCommands(const double *i_commands)
00459 {
00460     if (!m_commandOld.size()) {
00461         m_commandOld.resize(numJoints());
00462         m_velocityOld.resize(numJoints());
00463     }
00464     for (unsigned int i=0; i<numJoints(); i++){
00465         m_velocityOld[i] = (i_commands[i] - m_commandOld[i])/m_dt;
00466         m_commandOld[i] = i_commands[i];
00467     }
00468     write_command_angles(i_commands);
00469 }
00470 
00471 void robot::readJointCommands(double *o_commands)
00472 {
00473     read_command_angles(o_commands);
00474 }
00475 
00476 void robot::writeTorqueCommands(const double *i_commands)
00477 {
00478     write_command_torques(i_commands);
00479 }
00480 
00481 void robot::writeVelocityCommands(const double *i_commands)
00482 {
00483     write_command_velocities(i_commands);
00484 }
00485 
00486 void robot::readPowerStatus(double &o_voltage, double &o_current)
00487 {
00488     read_power(&o_voltage, &o_current);
00489 }
00490 
00491 int robot::readCalibState(int i)
00492 {
00493     int v=0;
00494     read_calib_state(i, &v);
00495     return v;
00496 }
00497 
00498 int robot::readPowerState(int i)
00499 {
00500     int v=0;
00501     read_power_state(i, &v);
00502     return v;
00503 }
00504 
00505 int robot::readServoState(int i)
00506 {
00507     int v=0;
00508     read_servo_state(i, &v);
00509     return v;
00510 }
00511 
00512 int robot::readServoAlarm(int i)
00513 {
00514     int v=0;
00515     read_servo_alarm(i, &v);
00516     return v;
00517 }
00518 
00519 int robot::readDriverTemperature(int i)
00520 {
00521     unsigned char temp=0;
00522     read_driver_temperature(i, &temp);
00523     return temp;
00524 }
00525 
00526 char *time_string()
00527 {
00528     struct timeval tv;
00529     gettimeofday(&tv, NULL);
00530     struct tm *tm_ = localtime(&tv.tv_sec);
00531     static char time[20];
00532     sprintf(time, "%02d:%02d:%02d.%06d", tm_->tm_hour, tm_->tm_min, tm_->tm_sec, (int)tv.tv_usec);
00533     return time;
00534 }
00535 
00536 bool robot::checkJointCommands(const double *i_commands)
00537 {
00538     if (!m_dt) return false;
00539     if (!m_commandOld.size()) return false;
00540 
00541     int state;
00542     for (unsigned int i=0; i<numJoints(); i++){
00543         read_servo_state(i, &state);
00544         if (state == ON){
00545             double command_old=m_commandOld[i], command=i_commands[i];
00546             double v = (command - command_old)/m_dt;
00547             if (fabs(v) > joint(i)->uvlimit){
00548                 std::cerr << time_string()
00549                           << ": joint command velocity limit over: joint = " 
00550                           << joint(i)->name
00551                           << ", vlimit = " << joint(i)->uvlimit/M_PI*180 
00552                           << "[deg/s], v = " 
00553                           << v/M_PI*180 << "[deg/s]" << std::endl;
00554                 return true;
00555             }
00556             double a = (v - m_velocityOld[i])/m_dt;
00557             if (m_accLimit && fabs(a) > m_accLimit){
00558                 std::cerr << time_string()
00559                           << ": joint command acceleration limit over: joint = " 
00560                           << joint(i)->name
00561                           << ", alimit = " << m_accLimit/M_PI*180 
00562                           << "[deg/s^2], v = " 
00563                           << a/M_PI*180 << "[deg/s^2]" << std::endl;
00564                 return true;
00565             }
00566         }
00567     }
00568     return false;
00569 }
00570 
00571 bool robot::checkEmergency(emg_reason &o_reason, int &o_id)
00572 {
00573     int state;
00574     for (unsigned int i=0; i<numJoints(); i++){
00575         read_servo_state(i, &state);
00576         if (state == ON && m_servoErrorLimit[i] != 0){
00577             double angle, command;
00578             read_actual_angle(i, &angle);
00579             read_command_angle(i, &command);
00580             if (fabs(angle-command) > m_servoErrorLimit[i]){
00581                 std::cerr << time_string()
00582                           << ": servo error limit over: joint = " 
00583                           << joint(i)->name
00584                           << ", qRef = " << command/M_PI*180 << "[deg], q = " 
00585                           << angle/M_PI*180 << "[deg]" << std::endl;
00586                 o_reason = EMG_SERVO_ERROR;
00587                 o_id = i;
00588                 return true;
00589             }
00590         }
00591     }
00592 
00593     if (m_rLegForceSensorId >= 0){
00594         double force[6];
00595         read_force_sensor(m_rLegForceSensorId, force);
00596         if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
00597             std::cerr << time_string() << ": right Fz limit over: Fz = " << force[FZ] << std::endl;
00598             o_reason = EMG_FZ;
00599             o_id = m_rLegForceSensorId;
00600             return true;
00601         }
00602     } 
00603     if (m_lLegForceSensorId >= 0){
00604         double force[6];
00605         read_force_sensor(m_lLegForceSensorId, force);
00606         if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
00607             std::cerr << time_string() << ": left Fz limit over: Fz = " << force[FZ] << std::endl;
00608             o_reason = EMG_FZ;
00609             o_id = m_lLegForceSensorId;
00610             return true;
00611         }
00612     } 
00613     int alarm;
00614     for (unsigned int i=0; i<numJoints(); i++){
00615         if (!read_servo_alarm(i, &alarm)) continue;
00616         if (alarm & SS_EMERGENCY) {
00617             if (!m_reportedEmergency) {
00618                 m_reportedEmergency = true;
00619                 o_reason = EMG_SERVO_ALARM;
00620                 o_id = i;
00621             }
00622             return true;
00623         }
00624     }
00625     m_reportedEmergency = false;
00626     // Power state check
00627     if (m_enable_poweroff_check) {
00628       int pstate, sstate;
00629       for (unsigned int i=0; i<numJoints(); i++){
00630         read_power_state(i, &pstate);
00631         read_servo_state(i, &sstate);
00632         // If power OFF while servo ON
00633         if (!m_reportedEmergency && (pstate == OFF) && (sstate == ON) ) {
00634           m_reportedEmergency = true;
00635           o_reason = EMG_POWER_OFF;
00636           o_id = i;
00637           std::cerr << time_string() << ": power off detected : joint = " << joint(i)->name << std::endl;
00638           return true;
00639         }
00640       }
00641       m_reportedEmergency = false;
00642     }
00643     return false;
00644 }
00645 
00646 bool robot::setServoGainPercentage(const char *i_jname, double i_percentage)
00647 {
00648     if ( i_percentage < 0 || 100 < i_percentage ) {
00649         std::cerr << "[RobotHardware] Invalid percentage " <<  i_percentage << "[%] for setServoGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
00650         return false;
00651     }
00652     Link *l = NULL;
00653     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00654         for (unsigned int i=0; i<numJoints(); i++){
00655             if (!read_pgain(i, &old_pgain[i])) old_pgain[i] = pgain[i];
00656             pgain[i] = default_pgain[i] * i_percentage/100.0;
00657             if (!read_dgain(i, &old_dgain[i])) old_dgain[i] = dgain[i];
00658             dgain[i] = default_dgain[i] * i_percentage/100.0;
00659             gain_counter[i] = 0;
00660         }
00661         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for all joints" << std::endl;
00662     }else if ((l = link(i_jname))){
00663         if (!read_pgain(l->jointId, &old_pgain[l->jointId])) old_pgain[l->jointId] = pgain[l->jointId];
00664         pgain[l->jointId] = default_pgain[l->jointId] * i_percentage/100.0;
00665         if (!read_dgain(l->jointId, &old_dgain[l->jointId])) old_dgain[l->jointId] = dgain[l->jointId];
00666         dgain[l->jointId] = default_dgain[l->jointId] * i_percentage/100.0;
00667         gain_counter[l->jointId] = 0;
00668         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00669     }else{
00670         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00671         const std::vector<int> jgroup = m_jointGroups[i_jname];
00672         if (jgroup.size()==0) return false;
00673         for (unsigned int i=0; i<jgroup.size(); i++){
00674             if (!read_pgain(jgroup[i], &old_pgain[jgroup[i]])) old_pgain[jgroup[i]] = pgain[jgroup[i]];
00675             pgain[jgroup[i]] = default_pgain[jgroup[i]] * i_percentage/100.0;
00676             if (!read_dgain(jgroup[i], &old_dgain[jgroup[i]])) old_dgain[jgroup[i]] = dgain[jgroup[i]];
00677             dgain[jgroup[i]] = default_dgain[jgroup[i]] * i_percentage/100.0;
00678             gain_counter[jgroup[i]] = 0;
00679         }
00680         std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
00681     }
00682     return true;
00683 }
00684 
00685 bool robot::setServoErrorLimit(const char *i_jname, double i_limit)
00686 {
00687     Link *l = NULL;
00688     if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
00689         for (unsigned int i=0; i<numJoints(); i++){
00690             m_servoErrorLimit[i] = i_limit;
00691         }
00692     }else if ((l = link(i_jname))){
00693         m_servoErrorLimit[l->jointId] = i_limit;
00694     }else{
00695         char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
00696         const std::vector<int> jgroup = m_jointGroups[i_jname];
00697         if (jgroup.size()==0) return false;
00698         for (unsigned int i=0; i<jgroup.size(); i++){
00699             m_servoErrorLimit[jgroup[i]] = i_limit;
00700         }
00701     }
00702     return true;
00703 }
00704 
00705 void robot::setProperty(const char *i_key, const char *i_value)
00706 {
00707     std::istringstream iss(i_value);
00708     std::string key(i_key);
00709     bool isKnownKey = true;
00710     if (key == "sensor_id.right_leg_force_sensor"){
00711         iss >> m_rLegForceSensorId;
00712     }else if (key == "sensor_id.left_leg_force_sensor"){
00713         iss >> m_lLegForceSensorId;
00714     }else if (key == "pdgains.file_name"){
00715         iss >> m_pdgainsFilename;
00716     }else if (key == "enable_poweroff_check"){
00717         std::string tmp;
00718         iss >> tmp;
00719         m_enable_poweroff_check = (tmp=="true");
00720     }else{
00721         isKnownKey = false;
00722     }
00723     if (isKnownKey) std::cout << i_key << ": " << i_value << std::endl;
00724 }
00725 
00726 bool robot::names2ids(const std::vector<std::string> &i_names, 
00727                             std::vector<int> &o_ids)
00728 { 
00729     bool ret = true;
00730     for (unsigned int i=0; i<i_names.size(); i++){
00731         Link *l = link(i_names[i].c_str());
00732         if (!l){
00733             std::cout << "joint named [" << i_names[i] << "] not found" 
00734                       << std::endl;
00735             ret = false;
00736         }else{
00737             o_ids.push_back(l->jointId);
00738         }
00739     }
00740     return ret;
00741 }
00742 
00743 bool robot::addJointGroup(const char *gname, const std::vector<std::string>& jnames)
00744 {
00745     char *s = (char *)gname; while(*s) {*s=toupper(*s);s++;}
00746     std::vector<int> jids;
00747     bool ret = names2ids(jnames, jids);
00748     m_jointGroups[gname] = jids;
00749     return ret;
00750 }
00751 
00752 size_t robot::lengthOfExtraServoState(int id)
00753 {
00754     return length_of_extra_servo_state(id);
00755 }
00756 
00757 void robot::readExtraServoState(int id, int *state)
00758 {
00759     read_extra_servo_state(id, state);
00760 }
00761 
00762 bool robot::readDigitalInput(char *o_din)
00763 {
00764 #ifndef NO_DIGITAL_INPUT
00765     return read_digital_input(o_din);
00766 #else
00767     return false;
00768 #endif
00769 }
00770 
00771 int robot::lengthDigitalInput()
00772 {
00773 #ifndef NO_DIGITAL_INPUT
00774     return length_digital_input();
00775 #else
00776     return 0;
00777 #endif
00778 }
00779 
00780 bool robot::writeDigitalOutput(const char *i_dout)
00781 {
00782     return write_digital_output(i_dout);
00783 }
00784 
00785 bool robot::writeDigitalOutputWithMask(const char *i_dout, const char *i_mask)
00786 {
00787     return write_digital_output_with_mask(i_dout, i_mask);
00788 }
00789 
00790 int robot::lengthDigitalOutput()
00791 {
00792     return length_digital_output();
00793 }
00794 
00795 bool robot::readDigitalOutput(char *o_dout)
00796 {
00797     return read_digital_output(o_dout);
00798 }
00799 
00800 void robot::readBatteryState(unsigned int i_rank, double &voltage, 
00801                              double &current, double &soc)
00802 {
00803 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00804     read_battery(i_rank, &voltage, &current, &soc);
00805 #else
00806     voltage=0; current=0; soc=0;
00807 #endif
00808 }
00809 
00810 int robot::numBatteries()
00811 {
00812 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00813     return number_of_batteries();
00814 #else
00815     return 0;
00816 #endif
00817 }
00818 
00819 void robot::readThermometer(unsigned int i_rank, double &o_temp)
00820 {
00821 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00822     read_temperature(i_rank, &o_temp);
00823 #else
00824     o_temp=0;
00825 #endif
00826 }
00827 
00828 int robot::numThermometers()
00829 {
00830 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00831     return number_of_thermometers();
00832 #else
00833     return 0;
00834 #endif
00835 }


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:55