RobotHardware/robot.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <cstdio>
3 #include <cstring>
4 #include <fstream>
5 #include <sys/time.h>
6 #include <hrpModel/Sensor.h>
7 #include <hrpModel/Link.h>
8 #include "defs.h"
9 #include "hrpsys/io/iob.h"
10 #include "robot.h"
11 #include "hrpsys/util/Hrpsys.h"
12 
13 #define CALIB_COUNT (10*200)
14 #define GAIN_COUNT ( 5*200)
15 
16 #define DEFAULT_MAX_ZMP_ERROR 0.03 //[m]
17 #define DEFAULT_ANGLE_ERROR_LIMIT 0.2 // [rad]
18 
19 using namespace hrp;
20 
21 
22 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)
23 {
24  sem_init(&wait_sem, 0, 0);
26 }
27 
29 {
30  close_iob();
31 }
32 
34 {
35  int i;
36  gain_counter.resize(numJoints());
37  for (unsigned i=0; i<numJoints(); i++){
39  }
40 
42 
43  pgain.resize(numJoints());
44  dgain.resize(numJoints());
45  old_pgain.resize(numJoints());
46  old_dgain.resize(numJoints());
47  default_pgain.resize(numJoints());
48  default_dgain.resize(numJoints());
49  tqpgain.resize(numJoints());
50  tqdgain.resize(numJoints());
51  old_tqpgain.resize(numJoints());
52  old_tqdgain.resize(numJoints());
53  default_tqpgain.resize(numJoints());
54  default_tqdgain.resize(numJoints());
55  for (unsigned int i=0; i<numJoints(); i++){
56  pgain[i] = dgain[i] = 0.0;
57  old_pgain[i] = old_dgain[i] = 0.0;
58  default_pgain[i] = default_dgain[i] = 0.0;
59  tqpgain[i] = tqdgain[i] = 0.0;
60  old_tqpgain[i] = old_tqdgain[i] = 0.0;
61  default_tqpgain[i] = default_tqdgain[i] = 0.0;
62  }
63  loadGain();
64  for (unsigned int i=0; i<numJoints(); i++){
65  pgain[i] = default_pgain[i];
66  dgain[i] = default_dgain[i];
67  tqpgain[i] = default_tqpgain[i];
68  tqdgain[i] = default_tqdgain[i];
69  }
70 
71  m_servoErrorLimit.resize(numJoints());
72  for (unsigned int i=0; i<numJoints(); i++){
74  }
75 
76 
77 
80  set_number_of_gyro_sensors(numSensors(Sensor::RATE_GYRO));
81  set_number_of_accelerometers(numSensors(Sensor::ACCELERATION));
82 
83  gyro_sum.resize(numSensors(Sensor::RATE_GYRO));
84  accel_sum.resize(numSensors(Sensor::ACCELERATION));
85  force_sum.resize(numSensors(Sensor::FORCE));
86 
87  if ((number_of_joints() != (int)numJoints())
88  || (number_of_force_sensors() != (int)numSensors(Sensor::FORCE))
89  || (number_of_gyro_sensors() != (int)numSensors(Sensor::RATE_GYRO))
90  || (number_of_accelerometers() != (int)numSensors(Sensor::ACCELERATION))){
91  std::cerr << "VRML and IOB are inconsistent" << std::endl;
92  std::cerr << " joints:" << numJoints() << "(VRML), " << number_of_joints() << "(IOB)" << std::endl;
93  std::cerr << " force sensor:" << numSensors(Sensor::FORCE) << "(VRML), " << number_of_force_sensors() << "(IOB)" << std::endl;
94  std::cerr << " gyro sensor:" << numSensors(Sensor::RATE_GYRO) << "(VRML), " << number_of_gyro_sensors() << "(IOB)" << std::endl;
95  std::cerr << " accelerometer:" << numSensors(Sensor::ACCELERATION) << "(VRML), " << number_of_accelerometers() << "(IOB)" << std::endl;
96  return false;
97  }
98  G << 0, 0, 9.8;
99 
100  if (open_iob() == FALSE) return false;
101 
102  return true;
103 }
104 
106 {
107  std::cerr << "[RobotHardware] removeForceSensorOffset..." << std::endl;
109  std::cerr << "[RobotHardware] removeForceSensorOffset...done." << std::endl;
110 }
111 
113 {
114  std::ifstream strm(m_pdgainsFilename.c_str());
115  if (!strm.is_open()) {
116  std::cerr << m_pdgainsFilename << " not found" << std::endl;
117  return false;
118  }
119 
120  for (int i = 0; i < numJoints(); i++) {
121  std::string str;
122  bool getlinep;
123  while ((getlinep = !!(std::getline(strm, str)))) {
124  if (str.empty()) {
125  // std::cerr << "[RobotHardware] : loadGain : skip emptiy line" << std::endl;
126  continue;
127  }
128  if (str[0] == '#') {
129  // std::cerr << "[RobotHardware] : loadGain : skip # started line" << std::endl;
130  continue;
131  }
132  double tmp;
133  std::istringstream sstrm(str);
134  sstrm >> tmp;
135  default_pgain[i] = tmp;
136  if(sstrm.eof()) break;
137 
138  sstrm >> tmp; // I gain
139  if(sstrm.eof()) break;
140 
141  sstrm >> tmp;
142  default_dgain[i] = tmp;
143  if(sstrm.eof()) break;
144 
145  sstrm >> tmp;
146  default_tqpgain[i] = tmp;
147  if(sstrm.eof()) break;
148 
149  sstrm >> tmp; // I gain for torque
150  if(sstrm.eof()) break;
151 
152  sstrm >> tmp;
153  default_tqdgain[i] = tmp;
154 
155  break;
156  }
157  if(!getlinep) {
158  if (i < numJoints()) {
159  std::cerr << "[RobotHardware] loadGain error: size of gains reading from file ("
161  << ") does not match size of joints" << std::endl;
162  }
163  break;
164  }
165  }
166 
167  strm.close();
168  // Print loaded gain
169  std::cerr << "[RobotHardware] loadGain" << std::endl;
170  for (unsigned int i=0; i<numJoints(); i++) {
171  std::cerr << "[RobotHardware] " << joint(i)->name
172  << ", pgain = " << default_pgain[i]
173  << ", dgain = " << default_dgain[i]
174  << ", tqpgain = " << default_tqpgain[i]
175  << ", tqdgain = " << default_tqdgain[i]
176  << std::endl;
177  }
178  return true;
179 }
180 
182 {
183  std::cerr << "[RobotHardware] startInertiaSensorCalibration..." << std::endl;
184  if (numSensors(Sensor::ACCELERATION)==0
185  && numSensors(Sensor::RATE_GYRO)==0) return;
186 
187  if (isBusy()) return;
188 
189  for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
190  for (int i=0; i<3; i++) {
191  gyro_sum[j][i] = 0;
192  }
194  }
195 
196  for(unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
197  for (int i=0; i<3; i++) {
198  accel_sum[j][i] = 0;
199  }
201  }
202 
203 #if 0
204  for(unsigned int j=0; j<m_natt; j++) {
205  for (int i=0; i<3; i++) {
206  att_sum[j][i] = 0;
207  }
209  }
210 #endif
211 
213 
214  sem_wait(&wait_sem);
215  std::cerr << "[RobotHardware] startInertiaSensorCalibration...done." << std::endl;
216 }
217 
219 {
220  if (numSensors(Sensor::FORCE)==0) return;
221 
222  if (isBusy()) return;
223 
224  for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
225  for (int i=0; i<6; i++) {
226  force_sum[j][i] = 0;
227  }
228  }
229 
231 
232  sem_wait(&wait_sem);
233 }
234 
235 void robot::initializeJointAngle(const char *name, const char *option)
236 {
238  m_calibOptions = option;
239  m_calibRequested = true;
240  sem_wait(&wait_sem);
241 }
242 
244 {
245  if (inertia_calib_counter>0) {
246  for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++){
247  double rate[3];
248  read_gyro_sensor(j, rate);
249  for (int i=0; i<3; i++)
250  gyro_sum[j][i] += rate[i];
251  }
252 
253  for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++){
254  double acc[3];
255  read_accelerometer(j, acc);
256  for (int i=0; i<3; i++)
257  accel_sum[j][i] += acc[i];
258  }
259 
260 #if 0
261  for (unsigned int j=0; j<m_natt; j++){
262  double att[3];
263  read_attitude_sensor(j, att);
264  for (int i=0; i<3; i++)
265  att_sum[j][i] += att[i];
266  }
267 #endif
268 
270  if (inertia_calib_counter==0) {
271 
272  for (unsigned int j=0; j<numSensors(Sensor::RATE_GYRO); j++) {
273  for (int i=0; i<3; i++) {
274  gyro_sum[j][i] = -gyro_sum[j][i]/CALIB_COUNT;
275  }
277  }
278 
279  for (unsigned int j=0; j<numSensors(Sensor::ACCELERATION); j++) {
281  hrp::Matrix33 m_sensorR = m_sensor->link->R * m_sensor->localR;
282  hrp::Vector3 G_rotated = m_sensorR.transpose() * G;
283  for (int i=0; i<3; i++) {
284  accel_sum[j][i] = -accel_sum[j][i]/CALIB_COUNT + G_rotated(i);
285  }
287  }
288 
289 #if 0
290  for (unsigned int j=0; j<m_natt; j++) {
291  for (int i=0; i<3; i++) {
292  att_sum[j][i] = -att_sum[j][i]/CALIB_COUNT;
293  }
295  }
296 #endif
297 
298  sem_post(&wait_sem);
299  }
300  }
301 }
302 
304 {
305  if (force_calib_counter>0) {
306  for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++){
307  double force[6];
308  read_force_sensor(j, force);
309  for (int i=0; i<6; i++)
310  force_sum[j][i] += force[i];
311  }
313  if (force_calib_counter==0) {
314 
315  for (unsigned int j=0; j<numSensors(Sensor::FORCE); j++) {
316  for (int i=0; i<6; i++) {
318  }
320  }
321 
322  sem_post(&wait_sem);
323  }
324  }
325 }
326 
328 {
329  double new_pgain=0,new_dgain=0,new_tqpgain=0,new_tqdgain=0;
330  if (gain_counter[i] < GAIN_COUNT){
331  gain_counter[i]++;
332  new_pgain = (pgain[i]-old_pgain[i])*gain_counter[i]/GAIN_COUNT + old_pgain[i];
333  new_dgain = (dgain[i]-old_dgain[i])*gain_counter[i]/GAIN_COUNT + old_dgain[i];
334  new_tqpgain = (tqpgain[i]-old_tqpgain[i])*gain_counter[i]/GAIN_COUNT + old_tqpgain[i];
335  new_tqdgain = (tqdgain[i]-old_tqdgain[i])*gain_counter[i]/GAIN_COUNT + old_tqdgain[i];
336  write_pgain(i, new_pgain);
337  write_dgain(i, new_dgain);
338 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
339  write_torque_pgain(i, new_tqpgain);
340  write_torque_dgain(i, new_tqdgain);
341 #endif
342  }
343 }
344 
346 {
347  int i;
348  for (unsigned i=0; i<numJoints(); i++) gain_control(i);
349 }
350 
352 {
355  gain_control();
356  if (m_calibRequested){
358  m_calibOptions.c_str());
359  m_calibRequested = false;
360  sem_post(&wait_sem);
361  }
362 }
363 
364 bool robot::servo(const char *jname, bool turnon)
365 {
366  Link *l = NULL;
367  if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
368  bool ret = true;
369  for (unsigned int i=0; i<numJoints(); i++){
370  ret = ret && servo(i, turnon);
371  if (turnon) usleep(m_servoOnDelay*1e6);
372  }
373  m_reportedEmergency = false;
374  return ret;
375  }else if ((l = link(jname))){
376  return servo(l->jointId, turnon);
377  }else{
378  char *s = (char *)jname; while(*s) {*s=toupper(*s);s++;}
379  const std::vector<int> jgroup = m_jointGroups[jname];
380  if (jgroup.size() == 0) return false;
381  bool ret = true;
382  for (unsigned int i=0; i<jgroup.size(); i++){
383  ret = ret && servo(jgroup[i], turnon);
384  return ret;
385  }
386  }
387  return false;
388 }
389 
390 bool robot::servo(int jid, bool turnon)
391 {
392  if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
393 
394  int com = OFF;
395 
396  if (turnon) {
397  com = ON;
398  }
399 
400  write_pgain(jid, 0);
401  write_dgain(jid, 0);
402  old_pgain[jid] = 0;
403  old_dgain[jid] = 0;
404 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
405  write_torque_pgain(jid, 0);
406  write_torque_dgain(jid, 0);
407 #endif
408  old_tqpgain[jid] = 0;
409  old_tqdgain[jid] = 0;
410  if (turnon){
411  double angle;
412  read_actual_angle(jid, &angle);
413  write_command_angle(jid, angle);
414  }
415  write_servo(jid, com);
416  if (turnon) gain_counter[jid] = 0;
417 
418  return true;
419 }
420 
421 
422 bool robot::power(const char *jname, bool turnon)
423 {
424  int jid = JID_INVALID;
425 
426  if (strcmp(jname, "all") == 0 || strcmp(jname, "ALL") == 0){
427  jid = JID_ALL;
428  }else{
429  Link *l = link(jname);
430  if (!l) return false;
431  jid = l->jointId;
432  }
433  return power(jid, turnon);
434 }
435 
436 bool robot::power(int jid, bool turnon)
437 {
438  if (jid == JID_INVALID || jid >= (int)numJoints()) return false;
439 
440  int com = OFF;
441 
442  if (turnon) {
443  for(unsigned int i=0; i<numJoints(); i++) {
444  int s;
445  read_servo_state(i, &s);
446  if (s == ON)
447  return false;
448  }
449  com = ON;
450  }
451 
452  // next part written as if there is a relay for each joint
453  // up to HRP2, TREX, PARASA there is only one.
454 
455  if(jid == JID_ALL) {
456  if (com == OFF) {
457  for (unsigned int i=0; i<numJoints(); i++) {
458  write_pgain(i, 0);
459  write_dgain(i, 0);
460 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
461  write_torque_pgain(i, 0);
462  write_torque_dgain(i, 0);
463 #endif
464  write_servo(i, com);
465  write_power_command(i, com);
466  }
467  } else
468  for (unsigned int i=0; i<numJoints(); i++)
469  write_power_command(i, com);
470  } else {
471  if (com == OFF) {
472  write_pgain(jid, 0);
473  write_dgain(jid, 0);
474 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
475  write_torque_pgain(jid, 0);
476  write_torque_dgain(jid, 0);
477 #endif
478  write_servo(jid, com);
479  write_power_command(jid, com);
480  } else {
481  write_power_command(jid, com);
482  }
483  }
484 
485  return true;
486 }
487 
488 bool robot::isBusy() const
489 {
491  return true;
492 
493  for (unsigned int i=0; i<numJoints(); i++) {
494  if (gain_counter[i] < GAIN_COUNT) {
495  return true;
496  }
497  }
498 
499  return false;
500 }
501 
502 void robot::readJointAngles(double *o_angles)
503 {
504  read_actual_angles(o_angles);
505 }
506 
507 void robot::readJointVelocities(double *o_velocities)
508 {
509  read_actual_velocities(o_velocities);
510 }
511 
512 int robot::readJointTorques(double *o_torques)
513 {
514  return read_actual_torques(o_torques);
515 }
516 
517 int robot::readJointCommandTorques(double *o_torques)
518 {
519  return read_command_torques(o_torques);
520 }
521 
522 void robot::readGyroSensor(unsigned int i_rank, double *o_rates)
523 {
524  read_gyro_sensor(i_rank, o_rates);
525 }
526 
527 void robot::readAccelerometer(unsigned int i_rank, double *o_accs)
528 {
529  read_accelerometer(i_rank, o_accs);
530 }
531 
532 void robot::readForceSensor(unsigned int i_rank, double *o_forces)
533 {
534  read_force_sensor(i_rank, o_forces);
535 }
536 
537 void robot::writeJointCommands(const double *i_commands)
538 {
539  if (!m_commandOld.size()) {
540  m_commandOld.resize(numJoints());
541  m_velocityOld.resize(numJoints());
542  }
543  for (unsigned int i=0; i<numJoints(); i++){
544  m_velocityOld[i] = (i_commands[i] - m_commandOld[i])/m_dt;
545  m_commandOld[i] = i_commands[i];
546  }
547  write_command_angles(i_commands);
548 }
549 
550 void robot::readJointCommands(double *o_commands)
551 {
552  read_command_angles(o_commands);
553 }
554 
555 void robot::writeTorqueCommands(const double *i_commands)
556 {
557  write_command_torques(i_commands);
558 }
559 
560 void robot::writeVelocityCommands(const double *i_commands)
561 {
562  write_command_velocities(i_commands);
563 }
564 
565 void robot::writeAccelerationCommands(const double *i_commands)
566 {
567 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
568  write_command_accelerations(i_commands);
569 #endif
570 }
571 
572 void robot::readPowerStatus(double &o_voltage, double &o_current)
573 {
574  read_power(&o_voltage, &o_current);
575 }
576 
578 {
579  int v=0;
580  read_calib_state(i, &v);
581  return v;
582 }
583 
585 {
586  int v=0;
587  read_power_state(i, &v);
588  return v;
589 }
590 
592 {
593  int v=0;
594  read_servo_state(i, &v);
595  return v;
596 }
597 
599 {
600  int v=0;
601  read_servo_alarm(i, &v);
602  return v;
603 }
604 
606 {
607  unsigned char temp=0;
608  read_driver_temperature(i, &temp);
609  return temp;
610 }
611 
612 char *time_string()
613 {
614  struct timeval tv;
615  gettimeofday(&tv, NULL);
616  struct tm *tm_ = localtime(&tv.tv_sec);
617  static char time[20];
618  sprintf(time, "%02d:%02d:%02d.%06d", tm_->tm_hour, tm_->tm_min, tm_->tm_sec, (int)tv.tv_usec);
619  return time;
620 }
621 
622 bool robot::checkJointCommands(const double *i_commands)
623 {
624  if (!m_dt) return false;
625  if (!m_commandOld.size()) return false;
626 
627  int state;
628  for (unsigned int i=0; i<numJoints(); i++){
629  read_servo_state(i, &state);
630  if (state == ON){
631  double command_old=m_commandOld[i], command=i_commands[i];
632  double v = (command - command_old)/m_dt;
633  if (fabs(v) > joint(i)->uvlimit){
634  std::cerr << time_string()
635  << ": joint command velocity limit over: joint = "
636  << joint(i)->name
637  << ", vlimit = " << joint(i)->uvlimit/M_PI*180
638  << "[deg/s], v = "
639  << v/M_PI*180 << "[deg/s]" << std::endl;
640  return true;
641  }
642  double a = (v - m_velocityOld[i])/m_dt;
643  if (m_accLimit && fabs(a) > m_accLimit){
644  std::cerr << time_string()
645  << ": joint command acceleration limit over: joint = "
646  << joint(i)->name
647  << ", alimit = " << m_accLimit/M_PI*180
648  << "[deg/s^2], v = "
649  << a/M_PI*180 << "[deg/s^2]" << std::endl;
650  return true;
651  }
652  }
653  }
654  return false;
655 }
656 
657 bool robot::checkEmergency(emg_reason &o_reason, int &o_id)
658 {
659  int state;
660  for (unsigned int i=0; i<numJoints(); i++){
661  read_servo_state(i, &state);
662  if (state == ON && m_servoErrorLimit[i] != 0){
663  double angle, command;
664  read_actual_angle(i, &angle);
665  read_command_angle(i, &command);
666  if (fabs(angle-command) > m_servoErrorLimit[i]){
667  std::cerr << time_string()
668  << ": servo error limit over: joint = "
669  << joint(i)->name
670  << ", qRef = " << command/M_PI*180 << "[deg], q = "
671  << angle/M_PI*180 << "[deg]" << std::endl;
672  o_reason = EMG_SERVO_ERROR;
673  o_id = i;
674  return true;
675  }
676  }
677  }
678 
679  if (m_rLegForceSensorId >= 0){
680  double force[6];
682  if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
683  std::cerr << time_string() << ": right Fz limit over: Fz = " << force[FZ] << std::endl;
684  o_reason = EMG_FZ;
685  o_id = m_rLegForceSensorId;
686  return true;
687  }
688  }
689  if (m_lLegForceSensorId >= 0){
690  double force[6];
692  if (force[FZ] > totalMass()*G(2)*m_fzLimitRatio){
693  std::cerr << time_string() << ": left Fz limit over: Fz = " << force[FZ] << std::endl;
694  o_reason = EMG_FZ;
695  o_id = m_lLegForceSensorId;
696  return true;
697  }
698  }
699  int alarm;
700  for (unsigned int i=0; i<numJoints(); i++){
701  if (!read_servo_alarm(i, &alarm)) continue;
702  if (alarm & SS_EMERGENCY) {
703  if (!m_reportedEmergency) {
704  m_reportedEmergency = true;
705  o_reason = EMG_SERVO_ALARM;
706  o_id = i;
707  }
708  return true;
709  }
710  }
711  m_reportedEmergency = false;
712  // Power state check
714  int pstate, sstate;
715  for (unsigned int i=0; i<numJoints(); i++){
716  read_power_state(i, &pstate);
717  read_servo_state(i, &sstate);
718  // If power OFF while servo ON
719  if (!m_reportedEmergency && (pstate == OFF) && (sstate == ON) ) {
720  m_reportedEmergency = true;
721  o_reason = EMG_POWER_OFF;
722  o_id = i;
723  std::cerr << time_string() << ": power off detected : joint = " << joint(i)->name << std::endl;
724  return true;
725  }
726  }
727  m_reportedEmergency = false;
728  }
729  return false;
730 }
731 
732 bool robot::setServoGainPercentage(const char *i_jname, double i_percentage)
733 {
734  if ( i_percentage < 0 || 100 < i_percentage ) {
735  std::cerr << "[RobotHardware] Invalid percentage " << i_percentage << "[%] for setServoGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
736  return false;
737  }
738  Link *l = NULL;
739  if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
740  for (unsigned int i=0; i<numJoints(); i++){
741  if (!read_pgain(i, &old_pgain[i])) old_pgain[i] = pgain[i];
742  pgain[i] = default_pgain[i] * i_percentage/100.0;
743  if (!read_dgain(i, &old_dgain[i])) old_dgain[i] = dgain[i];
744  dgain[i] = default_dgain[i] * i_percentage/100.0;
745 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
746  if (!read_torque_pgain(i, &old_tqpgain[i])) old_tqpgain[i] = tqpgain[i];
747  if (!read_torque_dgain(i, &old_tqdgain[i])) old_tqdgain[i] = tqdgain[i];
748 #endif
749  gain_counter[i] = 0;
750  }
751  std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for all joints" << std::endl;
752  }else if ((l = link(i_jname))){
753  if (!read_pgain(l->jointId, &old_pgain[l->jointId])) old_pgain[l->jointId] = pgain[l->jointId];
754  pgain[l->jointId] = default_pgain[l->jointId] * i_percentage/100.0;
755  if (!read_dgain(l->jointId, &old_dgain[l->jointId])) old_dgain[l->jointId] = dgain[l->jointId];
756  dgain[l->jointId] = default_dgain[l->jointId] * i_percentage/100.0;
757 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
758  if (!read_torque_pgain(l->jointId, &old_tqpgain[l->jointId])) old_tqpgain[l->jointId] = tqpgain[l->jointId];
759  if (!read_torque_dgain(l->jointId, &old_tqdgain[l->jointId])) old_tqdgain[l->jointId] = tqdgain[l->jointId];
760 #endif
761  gain_counter[l->jointId] = 0;
762  std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
763  }else{
764  char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
765  const std::vector<int> jgroup = m_jointGroups[i_jname];
766  if (jgroup.size()==0) return false;
767  for (unsigned int i=0; i<jgroup.size(); i++){
768  if (!read_pgain(jgroup[i], &old_pgain[jgroup[i]])) old_pgain[jgroup[i]] = pgain[jgroup[i]];
769  pgain[jgroup[i]] = default_pgain[jgroup[i]] * i_percentage/100.0;
770  if (!read_dgain(jgroup[i], &old_dgain[jgroup[i]])) old_dgain[jgroup[i]] = dgain[jgroup[i]];
771  dgain[jgroup[i]] = default_dgain[jgroup[i]] * i_percentage/100.0;
772 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
773  if (!read_torque_pgain(jgroup[i], &old_tqpgain[jgroup[i]])) old_tqpgain[jgroup[i]] = tqpgain[jgroup[i]];
774  if (!read_torque_dgain(jgroup[i], &old_tqdgain[jgroup[i]])) old_tqdgain[jgroup[i]] = tqdgain[jgroup[i]];
775 #endif
776  gain_counter[jgroup[i]] = 0;
777  }
778  std::cerr << "[RobotHardware] setServoGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
779  }
780  return true;
781 }
782 
783 bool robot::setServoTorqueGainPercentage(const char *i_jname, double i_percentage)
784 {
785  if ( i_percentage < 0 && 100 < i_percentage ) {
786  std::cerr << "[RobotHardware] Invalid percentage " << i_percentage << "[%] for setServoTorqueGainPercentage. Percentage should be in (0, 100)[%]." << std::endl;
787  return false;
788  }
789  Link *l = NULL;
790  if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
791  for (int i=0; i<numJoints(); i++){
792 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
793  if (!read_torque_pgain(i, &old_tqpgain[i])) old_tqpgain[i] = tqpgain[i];
794  tqpgain[i] = default_tqpgain[i] * i_percentage/100.0;
795  if (!read_torque_dgain(i, &old_tqdgain[i])) old_tqdgain[i] = tqdgain[i];
796  tqdgain[i] = default_tqdgain[i] * i_percentage/100.0;
797 #endif
798  if (!read_pgain(i, &old_pgain[i])) old_pgain[i] = pgain[i];
799  if (!read_dgain(i, &old_dgain[i])) old_dgain[i] = dgain[i];
800  gain_counter[i] = 0;
801  }
802  std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for all joints" << std::endl;
803  }else if ((l = link(i_jname))){
804 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
805  if (!read_torque_pgain(l->jointId, &old_tqpgain[l->jointId])) old_tqpgain[l->jointId] = tqpgain[l->jointId];
806  tqpgain[l->jointId] = default_tqpgain[l->jointId] * i_percentage/100.0;
807  if (!read_torque_dgain(l->jointId, &old_tqdgain[l->jointId])) old_tqdgain[l->jointId] = tqdgain[l->jointId];
808  tqdgain[l->jointId] = default_tqdgain[l->jointId] * i_percentage/100.0;
809 #endif
810  if (!read_pgain(l->jointId, &old_pgain[l->jointId])) old_pgain[l->jointId] = pgain[l->jointId];
811  if (!read_dgain(l->jointId, &old_dgain[l->jointId])) old_dgain[l->jointId] = dgain[l->jointId];
812  gain_counter[l->jointId] = 0;
813  std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
814  }else{
815  char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
816  const std::vector<int> jgroup = m_jointGroups[i_jname];
817  if (jgroup.size()==0) return false;
818  for (unsigned int i=0; i<jgroup.size(); i++){
819 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
820  if (!read_torque_pgain(jgroup[i], &old_tqpgain[jgroup[i]])) old_tqpgain[jgroup[i]] = tqpgain[jgroup[i]];
821  tqpgain[jgroup[i]] = default_tqpgain[jgroup[i]] * i_percentage/100.0;
822  if (!read_torque_dgain(jgroup[i], &old_tqdgain[jgroup[i]])) old_tqdgain[jgroup[i]] = tqdgain[jgroup[i]];
823  tqdgain[jgroup[i]] = default_tqdgain[jgroup[i]] * i_percentage/100.0;
824 #endif
825  if (!read_pgain(jgroup[i], &old_pgain[jgroup[i]])) old_pgain[jgroup[i]] = pgain[jgroup[i]];
826  if (!read_dgain(jgroup[i], &old_dgain[jgroup[i]])) old_dgain[jgroup[i]] = dgain[jgroup[i]];
827  gain_counter[jgroup[i]] = 0;
828  }
829  std::cerr << "[RobotHardware] setServoTorqueGainPercentage " << i_percentage << "[%] for " << i_jname << std::endl;
830  }
831  return true;
832 }
833 
834 bool robot::setServoErrorLimit(const char *i_jname, double i_limit)
835 {
836  Link *l = NULL;
837  if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0){
838  for (unsigned int i=0; i<numJoints(); i++){
839  m_servoErrorLimit[i] = i_limit;
840  }
841  }else if ((l = link(i_jname))){
842  m_servoErrorLimit[l->jointId] = i_limit;
843  }else{
844  char *s = (char *)i_jname; while(*s) {*s=toupper(*s);s++;}
845  const std::vector<int> jgroup = m_jointGroups[i_jname];
846  if (jgroup.size()==0) return false;
847  for (unsigned int i=0; i<jgroup.size(); i++){
848  m_servoErrorLimit[jgroup[i]] = i_limit;
849  }
850  }
851  return true;
852 }
853 
854 void robot::setProperty(const char *i_key, const char *i_value)
855 {
856  std::istringstream iss(i_value);
857  std::string key(i_key);
858  bool isKnownKey = true;
859  if (key == "sensor_id.right_leg_force_sensor"){
860  iss >> m_rLegForceSensorId;
861  }else if (key == "sensor_id.left_leg_force_sensor"){
862  iss >> m_lLegForceSensorId;
863  }else if (key == "pdgains.file_name"){
864  iss >> m_pdgainsFilename;
865  }else if (key == "enable_poweroff_check"){
866  std::string tmp;
867  iss >> tmp;
868  m_enable_poweroff_check = (tmp=="true");
869  }else{
870  isKnownKey = false;
871  }
872  if (isKnownKey) std::cout << i_key << ": " << i_value << std::endl;
873 }
874 
875 bool robot::names2ids(const std::vector<std::string> &i_names,
876  std::vector<int> &o_ids)
877 {
878  bool ret = true;
879  for (unsigned int i=0; i<i_names.size(); i++){
880  Link *l = link(i_names[i].c_str());
881  if (!l){
882  std::cout << "joint named [" << i_names[i] << "] not found"
883  << std::endl;
884  ret = false;
885  }else{
886  o_ids.push_back(l->jointId);
887  }
888  }
889  return ret;
890 }
891 
892 bool robot::addJointGroup(const char *gname, const std::vector<std::string>& jnames)
893 {
894  char *s = (char *)gname; while(*s) {*s=toupper(*s);s++;}
895  std::vector<int> jids;
896  bool ret = names2ids(jnames, jids);
897  m_jointGroups[gname] = jids;
898  return ret;
899 }
900 
902 {
903  return length_of_extra_servo_state(id);
904 }
905 
906 void robot::readExtraServoState(int id, int *state)
907 {
908  read_extra_servo_state(id, state);
909 }
910 
911 bool robot::readDigitalInput(char *o_din)
912 {
913 #ifndef NO_DIGITAL_INPUT
914  return read_digital_input(o_din);
915 #else
916  return false;
917 #endif
918 }
919 
921 {
922 #ifndef NO_DIGITAL_INPUT
923  return length_digital_input();
924 #else
925  return 0;
926 #endif
927 }
928 
929 bool robot::writeDigitalOutput(const char *i_dout)
930 {
931  return write_digital_output(i_dout);
932 }
933 
934 bool robot::writeDigitalOutputWithMask(const char *i_dout, const char *i_mask)
935 {
936  return write_digital_output_with_mask(i_dout, i_mask);
937 }
938 
940 {
941  return length_digital_output();
942 }
943 
944 bool robot::readDigitalOutput(char *o_dout)
945 {
946  return read_digital_output(o_dout);
947 }
948 
949 void robot::readBatteryState(unsigned int i_rank, double &voltage,
950  double &current, double &soc)
951 {
952 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
953  read_battery(i_rank, &voltage, &current, &soc);
954 #else
955  voltage=0; current=0; soc=0;
956 #endif
957 }
958 
960 {
961 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
962  return number_of_batteries();
963 #else
964  return 0;
965 #endif
966 }
967 
968 void robot::readThermometer(unsigned int i_rank, double &o_temp)
969 {
970 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
971  read_temperature(i_rank, &o_temp);
972 #else
973  o_temp=0;
974 #endif
975 }
976 
978 {
979 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
980  return number_of_thermometers();
981 #else
982  return 0;
983 #endif
984 }
985 
986 bool robot::setJointInertia(const char *jname, double mn)
987 {
988 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
989  Link *l = link(jname);
990  if (!l) return false;
991  int jid = l->jointId;
992  return write_joint_inertia(jid, mn);
993 #else
994  return false;
995 #endif
996 }
997 
998 void robot::setJointInertias(const double *mns)
999 {
1000 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
1001  write_joint_inertias(mns);
1002 #endif
1003 }
1004 
1005 int robot::readPDControllerTorques(double *o_torques)
1006 {
1007 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
1008  return read_pd_controller_torques(o_torques);
1009 #else
1010  return 0;
1011 #endif
1012 }
1013 
1015 {
1016 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
1017  write_disturbance_observer(ON);
1018 #endif
1019 }
1020 
1022 {
1023 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
1024  write_disturbance_observer(OFF);
1025 #endif
1026 }
1027 
1029 {
1030 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
1031  write_disturbance_observer_gain(gain);
1032 #endif
1033 }
1034 
1035 bool robot::setJointControlMode(const char *i_jname, joint_control_mode mode)
1036 {
1037  Link *l = NULL;
1038  if (strcmp(i_jname, "all") == 0 || strcmp(i_jname, "ALL") == 0) {
1039  for (int i=0; i < numJoints(); i++) {
1040  write_control_mode(i, mode);
1041  }
1042  std::cerr << "[RobotHardware] setJointControlMode for all joints : " << mode << std::endl;
1043  } else if ((l = link(i_jname))) {
1044  write_control_mode(l->jointId, mode);
1045  std::cerr << "[RobotHardware] setJointControlMode for " << i_jname << " : " << mode << std::endl;
1046  } else {
1047  char *s = (char *)i_jname; while(*s) { *s=toupper(*s); s++; }
1048  const std::vector<int> jgroup = m_jointGroups[i_jname];
1049  if (jgroup.size()==0) return false;
1050  for (unsigned int i=0; i<jgroup.size(); i++) {
1051  write_control_mode(jgroup[i], mode);
1052  }
1053  std::cerr << "[RobotHardware] setJointControlMode for " << i_jname << " : " << mode << std::endl;
1054  }
1055  return true;
1056 }
void oneStep()
all processings for one sampling period
int write_dgain(int id, double gain)
write D gain[Nm/(rad/s)]
Definition: iob.cpp:291
int read_servo_state(int id, int *s)
read servo status
Definition: iob.cpp:179
std::vector< double > dgain
void enableDisturbanceObserver()
enable disturbance observer
int read_attitude_sensor(int id, double *att)
read output of attitude sensor
Definition: iob.cpp:330
std::vector< double > m_commandOld
int write_power_command(int id, int com)
turn on/off power supply for motor driver
Definition: iob.cpp:165
int read_command_angle(int id, double *angle)
read command angle[rad]
Definition: iob.cpp:246
void readThermometer(unsigned int i_rank, double &o_temp)
read thermometer
std::vector< double > tqdgain
int set_number_of_gyro_sensors(int num)
set the number of gyro sensors
Definition: iob.cpp:116
int read_dgain(int id, double *gain)
read D gain[Nm/(rad/s)]
Definition: iob.cpp:286
int read_calib_state(int id, int *s)
read callibration state of joint
Definition: iob.cpp:485
bool servo(int jid, bool turnon)
turn on/off joint servo
std::vector< double > old_pgain
#define FALSE
Definition: iob.h:19
void readPowerStatus(double &o_voltage, double &o_current)
read voltage and current of the robot power source
std::string m_calibJointName
state
int read_command_torques(double *torques)
read array of command torques[Nm]
Definition: iob.cpp:236
std::vector< double > pgain
int read_extra_servo_state(int id, int *state)
read extra servo states
Definition: iob.cpp:692
void writeVelocityCommands(const double *i_commands)
write array of reference velocities of joint servo
int numBatteries()
get the number of batteries
bool readDigitalInput(char *o_din)
int write_digital_output_with_mask(const char *doutput, const char *mask)
write_digital_output, non-applicable bits are nop
Definition: iob.cpp:729
double m_accLimit
std::vector< double > gain_counter
void startForceSensorCalibration()
start force sensor calibration and wait until finish
int close_iob(void)
close connection with joint servo process
Definition: iob.cpp:413
double m_servoOnDelay
int read_force_sensor(int id, double *forces)
read output of force sensor
Definition: iob.cpp:296
int number_of_accelerometers()
get the number of accelerometers
Definition: iob.cpp:80
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
int readPowerState(int i)
read power status of a joint servo
std::vector< boost::array< double, 6 > > force_sum
std::vector< boost::array< double, 3 > > att_sum
bool checkJointCommands(const double *i_commands)
check joint commands are valid or not
void calibrateForceSensorOneStep()
calibrate force sensor for one sampling period
int read_power(double *voltage, double *current)
read status of power source
Definition: iob.cpp:563
int readServoState(int i)
read servo status of a joint servo
std::vector< double > old_dgain
int number_of_gyro_sensors()
get the number of gyro sensors
Definition: iob.cpp:75
#define SS_EMERGENCY
Definition: iob.h:51
std::vector< boost::array< double, 3 > > gyro_sum
bool m_calibRequested
std::vector< double > default_pgain
png_uint_32 i
int read_actual_angle(int id, double *angle)
read current joint angle[rad]
Definition: iob.cpp:206
int open_iob(void)
open connection with joint servo process
Definition: iob.cpp:401
bool m_reportedEmergency
Matrix33 localR
unsigned int numSensors(int sensorType) const
int write_control_mode(int id, joint_control_mode s)
write joint control mode
Definition: iob.cpp:200
#define CALIB_COUNT
int length_digital_input()
get_digital_input_length
Definition: iob.cpp:719
int write_gyro_sensor_offset(int id, double *offset)
write offset values for gyro sensor output
Definition: iob.cpp:440
void setJointInertias(const double *i_mn)
set joint inertias
~robot()
destructor
int readDriverTemperature(int i)
read temperature of motor driver
size_t length_of_extra_servo_state(int id)
get length of extra servo states
Definition: iob.cpp:687
int length_digital_output()
get_digital_output_length
Definition: iob.cpp:734
double totalMass() const
Eigen::Vector3d Vector3
Definition: defs.h:7
int read_power_state(int id, int *s)
read power status of motor driver
Definition: iob.cpp:158
Eigen::Matrix3d Matrix33
std::map< std::string, std::vector< int > > m_jointGroups
int read_command_angles(double *angles)
read array of command angles[rad]
Definition: iob.cpp:260
int write_pgain(int id, double gain)
write P gain[Nm/rad]
Definition: iob.cpp:281
int set_number_of_accelerometers(int num)
set the number of accelerometers
Definition: iob.cpp:131
int gettimeofday(struct timeval *tv, struct timezone *tz)
int write_attitude_sensor_offset(int id, double *offset)
Definition: iob.cpp:480
std::string m_pdgainsFilename
bool isBusy() const
check if a calibration process is running or not if one of calibration processes is running...
char * time_string()
def j(str, encoding="cp932")
const std::string & name()
double m_dt
Definition: Beeper.cpp:24
bool names2ids(const std::vector< std::string > &i_names, std::vector< int > &o_ids)
void setProperty(const char *key, const char *value)
int write_digital_output(const char *doutput)
write_digital_output, non-applicable bits are nop
Definition: iob.cpp:724
void readJointCommands(double *o_commands)
read array of reference angles of joint servo
std::vector< boost::array< double, 3 > > accel_sum
std::vector< double > m_velocityOld
int read_actual_velocities(double *vels)
read actual angular velocities[rad/s]
Definition: iob.cpp:370
int read_gyro_sensor(int id, double *rates)
read output of gyro sensor
Definition: iob.cpp:305
int m_lLegForceSensorId
int number_of_force_sensors()
get the number of force sensors
Definition: iob.cpp:70
emg_reason
reasons of emergency
int number_of_joints()
get the number of joints
Definition: iob.cpp:65
int m_rLegForceSensorId
int read_driver_temperature(int id, unsigned char *v)
read temperature of motor driver[Celsius]
Definition: iob.cpp:649
#define JID_ALL
Definition: iob.h:54
void startInertiaSensorCalibration()
start inertia sensor calibration and wait until finish
void readAccelerometer(unsigned int i_rank, double *o_accs)
read accelerometer output
robot()
constructor
int read_temperature(int id, double *v)
read thermometer
Definition: iob.cpp:385
int readPDControllerTorques(double *o_torques)
read array of all pd controller torques[Nm]
Link * joint(int id) const
bool checkEmergency(emg_reason &o_reason, int &o_id)
check occurrence of emergency state
int read_accelerometer(int id, double *accels)
read output of accelerometer
Definition: iob.cpp:315
void writeJointCommands(const double *i_commands)
write array of reference angles of joint servo
Link * link(int index) const
bool addJointGroup(const char *gname, const std::vector< std::string > &jnames)
bool setJointControlMode(const char *i_jname, joint_control_mode mode)
set control mode of joint
int write_force_offset(int id, double *offsets)
write offset values for force sensor output
Definition: iob.cpp:472
#define M_PI
int readServoAlarm(int i)
read alarm information of a joint servo
int force_calib_counter
std::vector< double > default_dgain
void writeAccelerationCommands(const double *i_commands)
write array of reference accelerations of joint servo
void readJointVelocities(double *o_velocities)
read array of all joint velocities[rad/s]
int numThermometers()
get the number of thermometers
bool writeDigitalOutput(const char *i_dout)
std::string sprintf(char const *__restrict fmt,...)
void readGyroSensor(unsigned int i_rank, double *o_rates)
read gyro sensor output
std::vector< double > m_servoErrorLimit
std::vector< double > tqpgain
joint_control_mode
Definition: iob.h:61
unsigned int numJoints() const
int read_servo_alarm(int id, int *a)
read servo alarms
Definition: iob.cpp:186
int readJointCommandTorques(double *o_torques)
read array of all commanded joint torques[Nm]
int read_digital_output(char *doutput)
read_digital_output, non-applicable bits are nop
Definition: iob.cpp:739
int readCalibState(int i)
read calibration status of a joint servo
bool readDigitalOutput(char *o_dout)
std::vector< double > old_tqpgain
int lengthDigitalOutput()
bool setServoGainPercentage(const char *i_jname, double i_percentage)
set the parcentage to the default servo gain
bool writeDigitalOutputWithMask(const char *i_dout, const char *i_mask)
void readExtraServoState(int id, int *state)
read extra servo states
std::vector< double > default_tqpgain
#define GAIN_COUNT
void setDisturbanceObserverGain(double gain)
set disturbance observer gain
bool setServoErrorLimit(const char *i_jname, double i_limit)
set servo error limit value for specific joint or joint group
JSAMPIMAGE data
std::vector< double > default_tqdgain
int read_digital_input(char *dinput)
read_digital_input, non-applicable bits are nop
Definition: iob.cpp:714
int lengthDigitalInput()
bool loadGain()
load PD gains
int set_number_of_joints(int num)
set the number of joints
Definition: iob.cpp:90
#define DEFAULT_ANGLE_ERROR_LIMIT
void removeForceSensorOffset()
remove offsets on force sensor outputs
bool power(int jid, bool turnon)
turn on/off power for joint servo
static std::vector< double > command
Definition: iob.cpp:8
size_t lengthOfExtraServoState(int id)
get length of extra servo states
int write_servo(int id, int com)
turn on/off joint servo
Definition: iob.cpp:390
int inertia_calib_counter
bool m_enable_poweroff_check
void gain_control()
#define OFF
Definition: iob.h:9
#define ON
Definition: iob.h:8
bool setServoTorqueGainPercentage(const char *i_jname, double i_percentage)
set the parcentage to the default servo torque gain
void readJointAngles(double *o_angles)
read array of all joint angles[rad]
void calibrateInertiaSensorOneStep()
calibrate inertia sensor for one sampling period
void initializeJointAngle(const char *name, const char *option)
initialize joint angle
int set_number_of_force_sensors(int num)
set the number of force sensors
Definition: iob.cpp:101
std::vector< double > old_tqdgain
void readForceSensor(unsigned int i_rank, double *o_forces)
read force sensor output
std::string m_calibOptions
int readJointTorques(double *o_torques)
read array of all joint torques[Nm]
int write_command_velocities(const double *vels)
write command angular velocities[rad/s]
Definition: iob.cpp:380
void writeTorqueCommands(const double *i_commands)
write array of reference torques of joint servo
Sensor * sensor(int sensorType, int sensorId) const
double m_fzLimitRatio
void readBatteryState(unsigned int i_rank, double &o_voltage, double &o_current, double &o_soc)
read battery state
bool setJointInertia(const char *i_jname, double i_mn)
set joint inertia
int write_command_angle(int id, double angle)
write command angle[rad]
Definition: iob.cpp:253
int read_actual_angles(double *angles)
read array of current joint angles[rad]
Definition: iob.cpp:213
int usleep(useconds_t usec)
void disableDisturbanceObserver()
disable disturbance observer
hrp::Vector3 G
int write_command_torques(const double *torques)
write array of command torques[Nm]
Definition: iob.cpp:241
int write_command_angles(const double *angles)
write array of command angles[rad]
Definition: iob.cpp:268
int read_actual_torques(double *torques)
read array of current joint torques[Nm]
Definition: iob.cpp:221
#define DEFAULT_MAX_ZMP_ERROR
#define JID_INVALID
Definition: iob.h:55
int read_pgain(int id, double *gain)
read P gain[Nm/rad]
Definition: iob.cpp:276
int write_accelerometer_offset(int id, double *offset)
write offset values for accelerometer output
Definition: iob.cpp:456


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