00001 #include <unistd.h>
00002 #include <iostream>
00003 #include <cstdlib>
00004 #include <cstring>
00005 #include <vector>
00006 #include "iob.h"
00007
00008 static std::vector<double> command;
00009 static std::vector<std::vector<double> > forces;
00010 static std::vector<std::vector<double> > gyros;
00011 static std::vector<std::vector<double> > accelerometers;
00012 static std::vector<std::vector<double> > attitude_sensors;
00013 static std::vector<std::vector<double> > force_offset;
00014 static std::vector<std::vector<double> > gyro_offset;
00015 static std::vector<std::vector<double> > accel_offset;
00016 static std::vector<int> power;
00017 static std::vector<int> servo;
00018 static bool isLocked = false;
00019 static int frame = 0;
00020 static timespec g_ts;
00021 static long g_period_ns=5000000;
00022
00023 #define CHECK_JOINT_ID(id) if ((id) < 0 || (id) >= number_of_joints()) return E_ID
00024 #define CHECK_FORCE_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_force_sensors()) return E_ID
00025 #define CHECK_ACCELEROMETER_ID(id) if ((id) < 0 || (id) >= number_of_accelerometers()) return E_ID
00026 #define CHECK_GYRO_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_gyro_sensors()) return E_ID
00027 #define CHECK_ATTITUDE_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_attitude_sensors()) return E_ID
00028
00029 #if (defined __APPLE__)
00030 typedef int clockid_t;
00031 #define CLOCK_MONOTONIC 0
00032 #include <mach/mach_time.h>
00033 int clock_gettime(clockid_t clk_id, struct timespec *tp)
00034 {
00035 if (clk_id != CLOCK_MONOTONIC) return -1;
00036
00037 uint64_t clk;
00038 clk = mach_absolute_time();
00039
00040 static mach_timebase_info_data_t info = {0,0};
00041 if (info.denom == 0) mach_timebase_info(&info);
00042
00043 uint64_t elapsednano = clk * (info.numer / info.denom);
00044
00045 tp->tv_sec = elapsednano * 1e-9;
00046 tp->tv_nsec = elapsednano - (tp->tv_sec * 1e9);
00047 return 0;
00048 }
00049
00050 #define TIMER_ABSTIME 0
00051 int clock_nanosleep(clockid_t clk_id, int flags, struct timespec *tp,
00052 struct timespec *remain)
00053 {
00054 if (clk_id != CLOCK_MONOTONIC || flags != TIMER_ABSTIME) return -1;
00055
00056 static mach_timebase_info_data_t info = {0,0};
00057 if (info.denom == 0) mach_timebase_info(&info);
00058
00059 uint64_t clk = (tp->tv_sec*1e9 + tp->tv_nsec)/(info.numer/info.denom);
00060
00061 mach_wait_until(clk);
00062 return 0;
00063 }
00064 #endif
00065
00066
00067 int number_of_joints()
00068 {
00069 return (int)command.size();
00070 }
00071
00072 int number_of_force_sensors()
00073 {
00074 return (int)forces.size();
00075 }
00076
00077 int number_of_gyro_sensors()
00078 {
00079 return (int)gyros.size();
00080 }
00081
00082 int number_of_accelerometers()
00083 {
00084 return (int)accelerometers.size();
00085 }
00086
00087 int number_of_attitude_sensors()
00088 {
00089 return (int)attitude_sensors.size();
00090 }
00091
00092 int set_number_of_joints(int num)
00093 {
00094 command.resize(num);
00095 power.resize(num);
00096 servo.resize(num);
00097 for (int i=0; i<num; i++){
00098 command[i] = power[i] = servo[i] = 0;
00099 }
00100 return TRUE;
00101 }
00102
00103 int set_number_of_force_sensors(int num)
00104 {
00105 forces.resize(num);
00106 force_offset.resize(num);
00107 for (unsigned int i=0; i<forces.size();i++){
00108 forces[i].resize(6);
00109 force_offset[i].resize(6);
00110 for (int j=0; j<6; j++){
00111 forces[i][j] = 0;
00112 force_offset[i][j] = 0;
00113 }
00114 }
00115 return TRUE;
00116 }
00117
00118 int set_number_of_gyro_sensors(int num)
00119 {
00120 gyros.resize(num);
00121 gyro_offset.resize(num);
00122 for (unsigned int i=0; i<gyros.size();i++){
00123 gyros[i].resize(3);
00124 gyro_offset[i].resize(3);
00125 for (int j=0; j<3; j++){
00126 gyros[i][j] = 0.0;
00127 gyro_offset[i][j] = 0.0;
00128 }
00129 }
00130 return TRUE;
00131 }
00132
00133 int set_number_of_accelerometers(int num)
00134 {
00135 accelerometers.resize(num);
00136 accel_offset.resize(num);
00137 for (unsigned int i=0; i<accelerometers.size();i++){
00138 accelerometers[i].resize(3);
00139 accel_offset[i].resize(3);
00140 for (int j=0; j<3; j++){
00141 accelerometers[i][j] = j == 2 ? 9.81 : 0.0;
00142 accel_offset[i][j] = 0;
00143 }
00144 }
00145 return TRUE;
00146 }
00147
00148 int set_number_of_attitude_sensors(int num)
00149 {
00150 attitude_sensors.resize(num);
00151 for (unsigned int i=0; i<attitude_sensors.size();i++){
00152 attitude_sensors[i].resize(3);
00153 for (int j=0; j<3; j++){
00154 attitude_sensors[i][j] = 0.0;
00155 }
00156 }
00157 return TRUE;
00158 }
00159
00160 int read_power_state(int id, int *s)
00161 {
00162 CHECK_JOINT_ID(id);
00163 *s = power[id];
00164 return TRUE;
00165 }
00166
00167 int write_power_command(int id, int com)
00168 {
00169 CHECK_JOINT_ID(id);
00170 power[id] = com;
00171 return TRUE;
00172 }
00173
00174 int read_power_command(int id, int *com)
00175 {
00176 CHECK_JOINT_ID(id);
00177 *com = power[id];
00178 return TRUE;
00179 }
00180
00181 int read_servo_state(int id, int *s)
00182 {
00183 CHECK_JOINT_ID(id);
00184 *s = servo[id];
00185 return TRUE;
00186 }
00187
00188 int read_servo_alarm(int id, int *a)
00189 {
00190 CHECK_JOINT_ID(id);
00191 *a = 0;
00192 return TRUE;
00193 }
00194
00195 int read_control_mode(int id, joint_control_mode *s)
00196 {
00197 CHECK_JOINT_ID(id);
00198 *s = JCM_POSITION;
00199 return TRUE;
00200 }
00201
00202 int write_control_mode(int id, joint_control_mode s)
00203 {
00204 CHECK_JOINT_ID(id);
00205 return TRUE;
00206 }
00207
00208 int read_actual_angle(int id, double *angle)
00209 {
00210 CHECK_JOINT_ID(id);
00211 *angle = command[id]+0.01;
00212 return TRUE;
00213 }
00214
00215 int read_actual_angles(double *angles)
00216 {
00217 for (int i=0; i<number_of_joints(); i++){
00218 angles[i] = command[i]+0.01;
00219 }
00220 return TRUE;
00221 }
00222
00223 int read_actual_torques(double *torques)
00224 {
00225 return FALSE;
00226 }
00227
00228 int read_command_torque(int id, double *torque)
00229 {
00230 return FALSE;
00231 }
00232
00233 int write_command_torque(int id, double torque)
00234 {
00235 return FALSE;
00236 }
00237
00238 int read_command_torques(double *torques)
00239 {
00240 return FALSE;
00241 }
00242
00243 int write_command_torques(const double *torques)
00244 {
00245 return FALSE;
00246 }
00247
00248 int read_command_angle(int id, double *angle)
00249 {
00250 CHECK_JOINT_ID(id);
00251 *angle = command[id];
00252 return TRUE;
00253 }
00254
00255 int write_command_angle(int id, double angle)
00256 {
00257 CHECK_JOINT_ID(id);
00258 command[id] = angle;
00259 return TRUE;
00260 }
00261
00262 int read_command_angles(double *angles)
00263 {
00264 for (int i=0; i<number_of_joints(); i++){
00265 angles[i] = command[i];
00266 }
00267 return TRUE;
00268 }
00269
00270 int write_command_angles(const double *angles)
00271 {
00272 for (int i=0; i<number_of_joints(); i++){
00273 command[i] = angles[i];
00274 }
00275 return TRUE;
00276 }
00277
00278 int read_pgain(int id, double *gain)
00279 {
00280 return FALSE;
00281 }
00282
00283 int write_pgain(int id, double gain)
00284 {
00285 return FALSE;
00286 }
00287
00288 int read_dgain(int id, double *gain)
00289 {
00290 return FALSE;
00291 }
00292
00293 int write_dgain(int id, double gain)
00294 {
00295 return FALSE;
00296 }
00297
00298 int read_force_sensor(int id, double *forces)
00299 {
00300 for (int i=0; i<6; i++){
00301 forces[i] = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*2
00302 + 2 + force_offset[id][i];
00303 }
00304 return TRUE;
00305 }
00306
00307 int read_gyro_sensor(int id, double *rates)
00308 {
00309 CHECK_GYRO_SENSOR_ID(id);
00310 for (int i=0; i<3; i++){
00311 rates[i] = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.01
00312 + 0.01 + gyro_offset[id][i];
00313 }
00314 return TRUE;
00315 }
00316
00317 int read_accelerometer(int id, double *accels)
00318 {
00319 for (int i=0; i<3; i++){
00320 double randv = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.01;
00321 accels[i] = (i == 2 ? (9.8+randv) : randv)
00322 + 0.01 + accel_offset[id][i];
00323 }
00324 return TRUE;
00325 }
00326
00327 int read_touch_sensors(unsigned short *onoff)
00328 {
00329 return FALSE;
00330 }
00331
00332 int read_attitude_sensor(int id, double *att)
00333 {
00334 return FALSE;
00335 }
00336
00337 int read_current(int id, double *mcurrent)
00338 {
00339 return FALSE;
00340 }
00341
00342 int read_current_limit(int id, double *v)
00343 {
00344 return FALSE;
00345 }
00346
00347 int read_currents(double *currents)
00348 {
00349 return FALSE;
00350 }
00351
00352 int read_gauges(double *gauges)
00353 {
00354 return FALSE;
00355 }
00356
00357 int read_actual_velocity(int id, double *vel)
00358 {
00359 return FALSE;
00360 }
00361
00362 int read_command_velocity(int id, double *vel)
00363 {
00364 return FALSE;
00365 }
00366
00367 int write_command_velocity(int id, double vel)
00368 {
00369 return FALSE;
00370 }
00371
00372 int read_actual_velocities(double *vels)
00373 {
00374 return FALSE;
00375 }
00376
00377 int read_command_velocities(double *vels)
00378 {
00379 return FALSE;
00380 }
00381
00382 int write_command_velocities(const double *vels)
00383 {
00384 return FALSE;
00385 }
00386
00387 int read_temperature(int id, double *v)
00388 {
00389 return FALSE;
00390 }
00391
00392 int write_servo(int id, int com)
00393 {
00394 servo[id] = com;
00395 return TRUE;
00396 }
00397
00398 int write_dio(unsigned short buf)
00399 {
00400 return FALSE;
00401 }
00402
00403 int open_iob(void)
00404 {
00405 std::cout << "dummy IOB is opened" << std::endl;
00406 for (int i=0; i<number_of_joints(); i++){
00407 command[i] = 0.0;
00408 power[i] = OFF;
00409 servo[i] = OFF;
00410 }
00411 clock_gettime(CLOCK_MONOTONIC, &g_ts);
00412 return TRUE;
00413 }
00414
00415 int close_iob(void)
00416 {
00417 std::cout << "dummy IOB is closed" << std::endl;
00418 return TRUE;
00419 }
00420
00421 int reset_body(void)
00422 {
00423 for (int i=0; i<number_of_joints(); i++){
00424 power[i] = servo[i] = OFF;
00425 }
00426 return TRUE;
00427 }
00428
00429 int joint_calibration(int id, double angle)
00430 {
00431 return FALSE;
00432 }
00433
00434 int read_gyro_sensor_offset(int id, double *offset)
00435 {
00436 for (int i=0; i<3; i++){
00437 offset[i] = gyro_offset[id][i];
00438 }
00439 return TRUE;
00440 }
00441
00442 int write_gyro_sensor_offset(int id, double *offset)
00443 {
00444 for (int i=0; i<3; i++){
00445 gyro_offset[id][i] = offset[i];
00446 }
00447 return TRUE;
00448 }
00449
00450 int read_accelerometer_offset(int id, double *offset)
00451 {
00452 for (int i=0; i<3; i++){
00453 offset[i] = accel_offset[id][i];
00454 }
00455 return TRUE;
00456 }
00457
00458 int write_accelerometer_offset(int id, double *offset)
00459 {
00460 for (int i=0; i<3; i++){
00461 accel_offset[id][i] = offset[i];
00462 }
00463 return TRUE;
00464 }
00465
00466 int read_force_offset(int id, double *offsets)
00467 {
00468 for (int i=0; i<6; i++){
00469 offsets[i] = force_offset[id][i];
00470 }
00471 return TRUE;
00472 }
00473
00474 int write_force_offset(int id, double *offsets)
00475 {
00476 for (int i=0; i<6; i++){
00477 force_offset[id][i] = offsets[i];
00478 }
00479 return TRUE;
00480 }
00481
00482 int write_attitude_sensor_offset(int id, double *offset)
00483 {
00484 return FALSE;
00485 }
00486
00487 int read_calib_state(int id, int *s)
00488 {
00489 CHECK_JOINT_ID(id);
00490 int v = id/2;
00491 *s = v%2==0 ? ON : OFF;
00492 return TRUE;
00493 }
00494
00495 int lock_iob()
00496 {
00497 if (isLocked) return FALSE;
00498
00499 isLocked = true;
00500 return TRUE;
00501 }
00502 int unlock_iob()
00503 {
00504 isLocked = false;
00505 return TRUE;
00506 }
00507
00508 int read_lock_owner(pid_t *pid)
00509 {
00510 return FALSE;
00511 }
00512
00513 int read_limit_angle(int id, double *angle)
00514 {
00515 return FALSE;
00516 }
00517
00518 int read_angle_offset(int id, double *angle)
00519 {
00520 return FALSE;
00521 }
00522
00523 int write_angle_offset(int id, double angle)
00524 {
00525 return FALSE;
00526 }
00527
00528 int read_ulimit_angle(int id, double *angle)
00529 {
00530 return FALSE;
00531 }
00532 int read_llimit_angle(int id, double *angle)
00533 {
00534 return FALSE;
00535 }
00536 int read_encoder_pulse(int id, double *ec)
00537 {
00538 return FALSE;
00539 }
00540 int read_gear_ratio(int id, double *gr)
00541 {
00542 return FALSE;
00543 }
00544 int read_torque_const(int id, double *tc)
00545 {
00546 return FALSE;
00547 }
00548 int read_torque_limit(int id, double *limit)
00549 {
00550 return FALSE;
00551 }
00552
00553 unsigned long long read_iob_frame()
00554 {
00555 ++frame;
00556 if (frame == 5) frame = 0;
00557 return frame;
00558 }
00559
00560 int number_of_substeps()
00561 {
00562 return 5;
00563 }
00564
00565 int read_power(double *voltage, double *current)
00566 {
00567 *voltage = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*1+48;
00568 *current = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.5+1;
00569 return TRUE;
00570 }
00571
00572 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00573 int number_of_batteries()
00574 {
00575 return 1;
00576 }
00577
00578 int read_battery(int id, double *voltage, double *current, double *soc)
00579 {
00580 *voltage = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*1+48;
00581 *current = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.5+1;
00582 *soc = ((double)random()-RAND_MAX/2)/(RAND_MAX/2)*0.5+50;
00583 return TRUE;
00584 }
00585
00586 int number_of_thermometers()
00587 {
00588 return 0;
00589 }
00590
00591 #endif
00592
00593 int read_driver_temperature(int id, unsigned char *v)
00594 {
00595 *v = id * 2;
00596 return TRUE;
00597 }
00598
00599 void timespec_add_ns(timespec *ts, long ns)
00600 {
00601 ts->tv_nsec += ns;
00602 while (ts->tv_nsec > 1e9){
00603 ts->tv_sec += 1;
00604 ts->tv_nsec -= 1e9;
00605 }
00606 }
00607
00608 double timespec_compare(timespec *ts1, timespec *ts2)
00609 {
00610 double dts = ts1->tv_sec - ts2->tv_sec;
00611 double dtn = ts1->tv_nsec - ts2->tv_nsec;
00612 return dts*1e9+dtn;
00613 }
00614
00615 int wait_for_iob_signal()
00616 {
00617 clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &g_ts, 0);
00618 timespec_add_ns(&g_ts, g_period_ns);
00619 timespec now;
00620 clock_gettime(CLOCK_MONOTONIC, &now);
00621 double dt = timespec_compare(&g_ts, &now);
00622 if (dt <= 0){
00623
00624 do {
00625 timespec_add_ns(&g_ts, g_period_ns);
00626 }while(timespec_compare(&g_ts, &now)<=0);
00627 }
00628 return 0;
00629 }
00630
00631 size_t length_of_extra_servo_state(int id)
00632 {
00633 return 0;
00634 }
00635
00636 int read_extra_servo_state(int id, int *state)
00637 {
00638 return TRUE;
00639 }
00640
00641 int set_signal_period(long period_ns)
00642 {
00643 g_period_ns = period_ns;
00644 return TRUE;
00645 }
00646
00647 long get_signal_period()
00648 {
00649 return g_period_ns;
00650 }
00651
00652 int initializeJointAngle(const char *name, const char *option)
00653 {
00654 sleep(3);
00655 return TRUE;
00656 }
00657
00658 int read_digital_input(char *dinput)
00659 {
00660 return FALSE;
00661 }
00662
00663 int length_digital_input()
00664 {
00665 return 0;
00666 }
00667
00668 int write_digital_output(const char *doutput)
00669 {
00670 return FALSE;
00671 }
00672
00673 int write_digital_output_with_mask(const char *doutput, const char *mask)
00674 {
00675 return FALSE;
00676 }
00677
00678 int length_digital_output()
00679 {
00680 return 0;
00681 }
00682
00683 int read_digital_output(char *doutput)
00684 {
00685 return FALSE;
00686 }
00687
00688