iob.h
Go to the documentation of this file.
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         JCM_NUM 
00067     } joint_control_mode;
00068 
00072     // @{
00077     int number_of_joints();
00078 
00084     int set_number_of_joints(int num);
00085 
00090     int number_of_force_sensors();
00091 
00097     int set_number_of_force_sensors(int num);
00098 
00103     int number_of_gyro_sensors();
00104 
00110     int set_number_of_gyro_sensors(int num);
00111 
00116     int number_of_accelerometers();
00117 
00123     int set_number_of_accelerometers(int num);
00124 
00129     int number_of_attitude_sensors();
00130 
00131     // @}
00132 
00136     // @{
00145     int read_actual_angle(int id, double *angle);
00146 
00153     int read_actual_angles(double *angles);
00154 
00163     int read_angle_offset(int id, double *offset);
00164 
00173     int write_angle_offset(int id, double offset);
00174 
00176 
00177     // @name joint
00178     // @{
00187     int read_power_state(int id, int *s);
00188 
00197     int write_power_command(int id, int com);
00198 
00207     int read_power_command(int id, int *com);
00208 
00217     int read_servo_state(int id, int *s);
00218 
00227     int read_servo_alarm(int id, int *a);
00228     
00237     int read_control_mode(int id, joint_control_mode *s);
00238 
00247     int write_control_mode(int id, joint_control_mode s);
00248 
00255     int read_actual_torques(double *torques);
00256 
00265     int read_command_torque(int id, double *torque);
00266 
00273     int write_command_torque(int id, double torque);
00274 
00281     int read_command_torques(double *torques);
00282 
00289     int write_command_torques(const double *torques);
00290 
00298     int read_command_angle(int id, double *angle);
00299 
00306     int write_command_angle(int id, double angle);
00307 
00314     int read_command_angles(double *angles);
00315 
00322     int write_command_angles(const double *angles);
00323 
00330     int read_pgain(int id, double *gain);
00331 
00338     int write_pgain(int id, double gain);
00339 
00346     int read_dgain(int id, double *gain);
00347 
00354     int write_dgain(int id, double gain);
00355 
00362     int read_actual_velocity(int id, double *vel);
00363 
00370     int read_command_velocity(int id, double *vel);
00371 
00378     int write_command_velocity(int id, double vel);
00379 
00386     int read_actual_velocities(double *vels);
00387 
00394     int read_command_velocities(double *vels);
00395 
00402     int write_command_velocities(const double *vels);
00403 
00410     int write_servo(int id, int com);
00411 
00420     int read_driver_temperature(int id, unsigned char* v);
00421 
00430     int read_calib_state(int id, int *s);
00431 
00437     size_t length_of_extra_servo_state(int id);
00438 
00445     int read_extra_servo_state(int id, int *state);
00446 
00448 
00459     int read_force_sensor(int id, double *forces);
00460 
00469     int read_force_offset(int id, double *offsets);
00470 
00479     int write_force_offset(int id, double *offsets);
00481 
00492     int read_gyro_sensor(int id, double *rates);
00493 
00502     int read_gyro_sensor_offset(int id, double *offset);
00503 
00512     int write_gyro_sensor_offset(int id, double *offset);
00513 
00515 
00526     int read_accelerometer(int id, double *accels);
00527 
00536     int read_accelerometer_offset(int id, double *offset);
00537 
00546     int write_accelerometer_offset(int id, double *offset);
00547 
00549 
00562     int read_attitude_sensor(int id, double *att);
00563 
00564     int write_attitude_sensor_offset(int id, double *offset);
00566 
00577     int read_power(double *v, double *a);
00579 
00580 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
00581 
00582 
00586     int number_of_batteries();
00587 
00596     int read_battery(int id, double *v, double *a, double *b);
00597 
00602     int number_of_thermometers();
00603 
00605 #endif
00606 
00619     int read_temperature(int id, double *v);
00621 
00631     int open_iob(void);
00632 
00638     int close_iob(void);
00639 
00640     int reset_body(void);
00641 
00647     int lock_iob();
00648 
00652     int unlock_iob();
00653 
00657     int read_lock_owner(pid_t *pid);
00658 
00662     unsigned long long read_iob_frame();
00663 
00668     int number_of_substeps(); 
00669 
00674     int wait_for_iob_signal();
00675 
00681     int set_signal_period(long period_ns);
00682 
00687     long get_signal_period();
00688 
00695     int initializeJointAngle(const char *name, const char *option);
00696 
00702     int read_digital_input(char *dinput);
00703 
00708     int length_digital_input();
00709 
00715     int write_digital_output(const char *doutput);
00716 
00723     int write_digital_output_with_mask(const char *doutput, const char *dmask);
00724 
00729     int length_digital_output();
00730 
00736     int read_digital_output(char *doutput);
00738 
00739 #ifdef __cplusplus
00740 }
00741 #endif
00742 
00743 #endif


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