00001
00005 #ifndef __IOB_H__
00006 #define __IOB_H__
00007
00008 #define ON 1
00009 #define OFF 0
00010
00011 #define MASK_ON 0
00012 #define MASK_OFF 1
00013
00018 #ifndef FALSE
00019 #define FALSE 0
00020 #endif
00021
00022 #ifndef TRUE
00023 #define TRUE 1
00024 #endif
00025
00026 #define E_ID -1 ///< invalid joint(or sensor) id
00027
00028
00033 #define SS_OVER_VOLTAGE 0x001
00034 #define SS_OVER_LOAD 0x002
00035 #define SS_OVER_VELOCITY 0x004
00036 #define SS_OVER_CURRENT 0x008
00037
00038 #define SS_OVER_HEAT 0x010
00039 #define SS_TORQUE_LIMIT 0x020
00040 #define SS_VELOCITY_LIMIT 0x040
00041 #define SS_FORWARD_LIMIT 0x080
00042
00043 #define SS_REVERSE_LIMIT 0x100
00044 #define SS_POSITION_ERROR 0x200
00045 #define SS_ENCODER_ERROR 0x400
00046 #define SS_OTHER 0x800
00047
00048 #define SS_RESERVED1 0x1000
00049 #define SS_RESERVED2 0x2000
00050 #define SS_RESERVED3 0x4000
00051 #define SS_EMERGENCY 0x8000
00052
00053
00054 #define JID_ALL -1
00055 #define JID_INVALID -2
00056
00057 #ifdef __cplusplus
00058 extern "C"{
00059 #endif
00060
00061 typedef enum {
00062 JCM_FREE,
00063 JCM_POSITION,
00064 JCM_TORQUE,
00065 JCM_VELOCITY,
00066 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00067 JCM_POSITION_TORQUE,
00068 #endif
00069 JCM_NUM
00070 } joint_control_mode;
00071
00075
00080 int number_of_joints();
00081
00087 int set_number_of_joints(int num);
00088
00093 int number_of_force_sensors();
00094
00100 int set_number_of_force_sensors(int num);
00101
00106 int number_of_gyro_sensors();
00107
00113 int set_number_of_gyro_sensors(int num);
00114
00119 int number_of_accelerometers();
00120
00126 int set_number_of_accelerometers(int num);
00127
00132 int number_of_attitude_sensors();
00133
00134
00135
00139
00148 int read_actual_angle(int id, double *angle);
00149
00156 int read_actual_angles(double *angles);
00157
00166 int read_angle_offset(int id, double *offset);
00167
00176 int write_angle_offset(int id, double offset);
00177
00179
00180
00181
00190 int read_power_state(int id, int *s);
00191
00200 int write_power_command(int id, int com);
00201
00210 int read_power_command(int id, int *com);
00211
00220 int read_servo_state(int id, int *s);
00221
00230 int read_servo_alarm(int id, int *a);
00231
00240 int read_control_mode(int id, joint_control_mode *s);
00241
00250 int write_control_mode(int id, joint_control_mode s);
00251
00258 int read_actual_torques(double *torques);
00259
00268 int read_command_torque(int id, double *torque);
00269
00276 int write_command_torque(int id, double torque);
00277
00284 int read_command_torques(double *torques);
00285
00292 int write_command_torques(const double *torques);
00293
00301 int read_command_angle(int id, double *angle);
00302
00309 int write_command_angle(int id, double angle);
00310
00317 int read_command_angles(double *angles);
00318
00325 int write_command_angles(const double *angles);
00326
00333 int read_pgain(int id, double *gain);
00334
00341 int write_pgain(int id, double gain);
00342
00349 int read_dgain(int id, double *gain);
00350
00357 int write_dgain(int id, double gain);
00358
00365 int read_actual_velocity(int id, double *vel);
00366
00373 int read_command_velocity(int id, double *vel);
00374
00381 int write_command_velocity(int id, double vel);
00382
00389 int read_actual_velocities(double *vels);
00390
00397 int read_command_velocities(double *vels);
00398
00405 int write_command_velocities(const double *vels);
00406
00413 int write_servo(int id, int com);
00414
00423 int read_driver_temperature(int id, unsigned char* v);
00424
00433 int read_calib_state(int id, int *s);
00434
00440 size_t length_of_extra_servo_state(int id);
00441
00448 int read_extra_servo_state(int id, int *state);
00449
00451
00462 int read_force_sensor(int id, double *forces);
00463
00472 int read_force_offset(int id, double *offsets);
00473
00482 int write_force_offset(int id, double *offsets);
00484
00495 int read_gyro_sensor(int id, double *rates);
00496
00505 int read_gyro_sensor_offset(int id, double *offset);
00506
00515 int write_gyro_sensor_offset(int id, double *offset);
00516
00518
00529 int read_accelerometer(int id, double *accels);
00530
00539 int read_accelerometer_offset(int id, double *offset);
00540
00549 int write_accelerometer_offset(int id, double *offset);
00550
00552
00565 int read_attitude_sensor(int id, double *att);
00566
00567 int write_attitude_sensor_offset(int id, double *offset);
00569
00580 int read_power(double *v, double *a);
00582
00583 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00584
00592 int number_of_batteries();
00593
00602 int read_battery(int id, double *v, double *a, double *b);
00603
00608 int number_of_thermometers();
00609
00611 #endif
00612
00613 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
00614
00624 int write_command_acceleration(int id, double acc);
00625
00632 int write_command_accelerations(const double *accs);
00633
00640 int write_joint_inertia(int id, double mn);
00641
00648 int write_joint_inertias(const double *mns);
00649
00656 int read_pd_controller_torques(double *torques);
00657
00663 int write_disturbance_observer(int com);
00664
00670 int write_disturbance_observer_gain(double gain);
00672 #endif
00673
00674 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
00675
00685 int read_torque_pgain(int id, double *gain);
00686
00693 int write_torque_pgain(int id, double gain);
00694
00701 int read_torque_dgain(int id, double *gain);
00702
00709 int write_torque_dgain(int id, double gain);
00710
00712 #endif
00713
00726 int read_temperature(int id, double *v);
00728
00738 int open_iob(void);
00739
00745 int close_iob(void);
00746
00747 int reset_body(void);
00748
00754 int lock_iob();
00755
00759 int unlock_iob();
00760
00764 int read_lock_owner(pid_t *pid);
00765
00769 unsigned long long read_iob_frame();
00770
00775 int number_of_substeps();
00776
00781 int wait_for_iob_signal();
00782
00788 int set_signal_period(long period_ns);
00789
00794 long get_signal_period();
00795
00802 int initializeJointAngle(const char *name, const char *option);
00803
00809 int read_digital_input(char *dinput);
00810
00815 int length_digital_input();
00816
00822 int write_digital_output(const char *doutput);
00823
00830 int write_digital_output_with_mask(const char *doutput, const char *dmask);
00831
00836 int length_digital_output();
00837
00843 int read_digital_output(char *doutput);
00845
00846 #ifdef __cplusplus
00847 }
00848 #endif
00849
00850 #endif