iob.h
Go to the documentation of this file.
1 
5 #ifndef __IOB_H__
6 #define __IOB_H__
7 
8 #define ON 1
9 #define OFF 0
10 
11 #define MASK_ON 0
12 #define MASK_OFF 1
13 
18 #ifndef FALSE
19 #define FALSE 0
20 #endif
21 
22 #ifndef TRUE
23 #define TRUE 1
24 #endif
25 
26 #define E_ID -1
27 
28 
29 
33 #define SS_OVER_VOLTAGE 0x001
34 #define SS_OVER_LOAD 0x002
35 #define SS_OVER_VELOCITY 0x004
36 #define SS_OVER_CURRENT 0x008
37 
38 #define SS_OVER_HEAT 0x010
39 #define SS_TORQUE_LIMIT 0x020
40 #define SS_VELOCITY_LIMIT 0x040
41 #define SS_FORWARD_LIMIT 0x080
42 
43 #define SS_REVERSE_LIMIT 0x100
44 #define SS_POSITION_ERROR 0x200
45 #define SS_ENCODER_ERROR 0x400
46 #define SS_OTHER 0x800
47 
48 #define SS_RESERVED1 0x1000
49 #define SS_RESERVED2 0x2000
50 #define SS_RESERVED3 0x4000
51 #define SS_EMERGENCY 0x8000
52 
53 
54 #define JID_ALL -1
55 #define JID_INVALID -2
56 
57 #ifdef __cplusplus
58 extern "C"{
59 #endif
60 
61  typedef enum {
66 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
67  JCM_POSITION_TORQUE,
68 #endif
71 
75  // @{
80  int number_of_joints();
81 
87  int set_number_of_joints(int num);
88 
94 
100  int set_number_of_force_sensors(int num);
101 
107 
113  int set_number_of_gyro_sensors(int num);
114 
120 
126  int set_number_of_accelerometers(int num);
127 
133 
134  // @}
135 
139  // @{
148  int read_actual_angle(int id, double *angle);
149 
156  int read_actual_angles(double *angles);
157 
166  int read_angle_offset(int id, double *offset);
167 
176  int write_angle_offset(int id, double offset);
177 
179 
180  // @name joint
181  // @{
190  int read_power_state(int id, int *s);
191 
200  int write_power_command(int id, int com);
201 
210  int read_power_command(int id, int *com);
211 
220  int read_servo_state(int id, int *s);
221 
230  int read_servo_alarm(int id, int *a);
231 
240  int read_control_mode(int id, joint_control_mode *s);
241 
250  int write_control_mode(int id, joint_control_mode s);
251 
258  int read_actual_torques(double *torques);
259 
268  int read_command_torque(int id, double *torque);
269 
276  int write_command_torque(int id, double torque);
277 
284  int read_command_torques(double *torques);
285 
292  int write_command_torques(const double *torques);
293 
301  int read_command_angle(int id, double *angle);
302 
309  int write_command_angle(int id, double angle);
310 
317  int read_command_angles(double *angles);
318 
325  int write_command_angles(const double *angles);
326 
333  int read_pgain(int id, double *gain);
334 
341  int write_pgain(int id, double gain);
342 
349  int read_dgain(int id, double *gain);
350 
357  int write_dgain(int id, double gain);
358 
365  int read_actual_velocity(int id, double *vel);
366 
373  int read_command_velocity(int id, double *vel);
374 
381  int write_command_velocity(int id, double vel);
382 
389  int read_actual_velocities(double *vels);
390 
397  int read_command_velocities(double *vels);
398 
405  int write_command_velocities(const double *vels);
406 
413  int write_servo(int id, int com);
414 
423  int read_driver_temperature(int id, unsigned char* v);
424 
433  int read_calib_state(int id, int *s);
434 
440  size_t length_of_extra_servo_state(int id);
441 
448  int read_extra_servo_state(int id, int *state);
449 
451 
462  int read_force_sensor(int id, double *forces);
463 
472  int read_force_offset(int id, double *offsets);
473 
482  int write_force_offset(int id, double *offsets);
484 
495  int read_gyro_sensor(int id, double *rates);
496 
505  int read_gyro_sensor_offset(int id, double *offset);
506 
515  int write_gyro_sensor_offset(int id, double *offset);
516 
518 
529  int read_accelerometer(int id, double *accels);
530 
539  int read_accelerometer_offset(int id, double *offset);
540 
549  int write_accelerometer_offset(int id, double *offset);
550 
552 
565  int read_attitude_sensor(int id, double *att);
566 
567  int write_attitude_sensor_offset(int id, double *offset);
569 
580  int read_power(double *v, double *a);
582 
583 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2
584 
592  int number_of_batteries();
593 
602  int read_battery(int id, double *v, double *a, double *b);
603 
608  int number_of_thermometers();
609 
611 #endif
612 
613 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3
614 
624  int write_command_acceleration(int id, double acc);
625 
632  int write_command_accelerations(const double *accs);
633 
640  int write_joint_inertia(int id, double mn);
641 
648  int write_joint_inertias(const double *mns);
649 
656  int read_pd_controller_torques(double *torques);
657 
663  int write_disturbance_observer(int com);
664 
670  int write_disturbance_observer_gain(double gain);
672 #endif
673 
674 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4
675 
685  int read_torque_pgain(int id, double *gain);
686 
693  int write_torque_pgain(int id, double gain);
694 
701  int read_torque_dgain(int id, double *gain);
702 
709  int write_torque_dgain(int id, double gain);
710 
712 #endif
713 
726  int read_temperature(int id, double *v);
728 
738  int open_iob(void);
739 
745  int close_iob(void);
746 
747  int reset_body(void);
748 
754  int lock_iob();
755 
759  int unlock_iob();
760 
764  int read_lock_owner(pid_t *pid);
765 
769  unsigned long long read_iob_frame();
770 
775  int number_of_substeps();
776 
781  int wait_for_iob_signal();
782 
788  int set_signal_period(long period_ns);
789 
794  long get_signal_period();
795 
802  int initializeJointAngle(const char *name, const char *option);
803 
809  int read_digital_input(char *dinput);
810 
815  int length_digital_input();
816 
822  int write_digital_output(const char *doutput);
823 
830  int write_digital_output_with_mask(const char *doutput, const char *dmask);
831 
836  int length_digital_output();
837 
843  int read_digital_output(char *doutput);
845 
846 #ifdef __cplusplus
847 }
848 #endif
849 
850 #endif
int read_gyro_sensor(int id, double *rates)
read output of gyro sensor
Definition: iob.cpp:305
int read_pgain(int id, double *gain)
read P gain[Nm/rad]
Definition: iob.cpp:276
int read_force_sensor(int id, double *forces)
read output of force sensor
Definition: iob.cpp:296
int unlock_iob()
unlock access to iob
Definition: iob.cpp:500
static std::vector< std::vector< double > > forces
Definition: iob.cpp:9
int read_actual_velocities(double *vels)
read actual angular velocities[rad/s]
Definition: iob.cpp:370
int number_of_substeps()
Definition: iob.cpp:558
int read_servo_alarm(int id, int *a)
read servo alarms
Definition: iob.cpp:186
int write_accelerometer_offset(int id, double *offset)
write offset values for accelerometer output
Definition: iob.cpp:456
int read_power_state(int id, int *s)
read power status of motor driver
Definition: iob.cpp:158
int number_of_joints()
get the number of joints
Definition: iob.cpp:65
int read_angle_offset(int id, double *offset)
read offset value for joint[rad]
Definition: iob.cpp:516
int number_of_gyro_sensors()
get the number of gyro sensors
Definition: iob.cpp:75
int number_of_accelerometers()
get the number of accelerometers
Definition: iob.cpp:80
int wait_for_iob_signal()
wait until iob signal is issued
Definition: iob.cpp:671
int read_servo_state(int id, int *s)
read servo status
Definition: iob.cpp:179
int read_command_angles(double *angles)
read array of command angles[rad]
Definition: iob.cpp:260
torque control
Definition: iob.h:64
Definition: iob.h:69
int close_iob(void)
close connection with joint servo process
Definition: iob.cpp:413
int set_signal_period(long period_ns)
set the period of signals issued by wait_for_iob_signal()
Definition: iob.cpp:697
int write_control_mode(int id, joint_control_mode s)
write joint control mode
Definition: iob.cpp:200
int read_temperature(int id, double *v)
read thermometer
Definition: iob.cpp:385
::pid_t pid_t
int open_iob(void)
open connection with joint servo process
Definition: iob.cpp:401
int read_gyro_sensor_offset(int id, double *offset)
read offset values for gyro sensor output
Definition: iob.cpp:432
int write_servo(int id, int com)
turn on/off joint servo
Definition: iob.cpp:390
free
Definition: iob.h:62
int write_command_angle(int id, double angle)
write command angle[rad]
Definition: iob.cpp:253
int read_command_torques(double *torques)
read array of command torques[Nm]
Definition: iob.cpp:236
int read_actual_torques(double *torques)
read array of current joint torques[Nm]
Definition: iob.cpp:221
int read_actual_angle(int id, double *angle)
read current joint angle[rad]
Definition: iob.cpp:206
int set_number_of_gyro_sensors(int num)
set the number of gyro sensors
Definition: iob.cpp:116
int read_command_velocity(int id, double *vel)
read command angular velocity[rad/s]
Definition: iob.cpp:360
int read_accelerometer(int id, double *accels)
read output of accelerometer
Definition: iob.cpp:315
int read_command_torque(int id, double *torque)
read command torque[Nm]
Definition: iob.cpp:226
int reset_body(void)
Definition: iob.cpp:419
int write_dgain(int id, double gain)
write D gain[Nm/(rad/s)]
Definition: iob.cpp:291
int read_driver_temperature(int id, unsigned char *v)
read temperature of motor driver[Celsius]
Definition: iob.cpp:649
int set_number_of_joints(int num)
set the number of joints
Definition: iob.cpp:90
int write_pgain(int id, double gain)
write P gain[Nm/rad]
Definition: iob.cpp:281
int lock_iob()
lock access to iob
Definition: iob.cpp:493
int read_attitude_sensor(int id, double *att)
read output of attitude sensor
Definition: iob.cpp:330
int read_command_velocities(double *vels)
read command angular velocities[rad/s]
Definition: iob.cpp:375
int read_digital_output(char *doutput)
read_digital_output, non-applicable bits are nop
Definition: iob.cpp:739
int length_digital_output()
get_digital_output_length
Definition: iob.cpp:734
int write_command_angles(const double *angles)
write array of command angles[rad]
Definition: iob.cpp:268
int read_control_mode(int id, joint_control_mode *s)
read joint control mode
Definition: iob.cpp:193
int write_command_torque(int id, double torque)
write command torque[Nm]
Definition: iob.cpp:231
int read_lock_owner(pid_t *pid)
read id of the process whic is locking access to iob
Definition: iob.cpp:506
position control
Definition: iob.h:63
int write_digital_output_with_mask(const char *doutput, const char *dmask)
write_digital_output, non-applicable bits are nop
Definition: iob.cpp:729
int write_command_velocities(const double *vels)
write command angular velocities[rad/s]
Definition: iob.cpp:380
int read_calib_state(int id, int *s)
read callibration state of joint
Definition: iob.cpp:485
int read_actual_velocity(int id, double *vel)
read actual angular velocity[rad/s]
Definition: iob.cpp:355
joint_control_mode
Definition: iob.h:61
int read_accelerometer_offset(int id, double *offset)
read offset values for accelerometer output
Definition: iob.cpp:448
int read_dgain(int id, double *gain)
read D gain[Nm/(rad/s)]
Definition: iob.cpp:286
int number_of_attitude_sensors()
get the number of attitude sensors
Definition: iob.cpp:85
int write_power_command(int id, int com)
turn on/off power supply for motor driver
Definition: iob.cpp:165
int write_digital_output(const char *doutput)
write_digital_output, non-applicable bits are nop
Definition: iob.cpp:724
velocity control
Definition: iob.h:65
int read_actual_angles(double *angles)
read array of current joint angles[rad]
Definition: iob.cpp:213
int initializeJointAngle(const char *name, const char *option)
initialize joint angle
Definition: iob.cpp:708
int write_command_torques(const double *torques)
write array of command torques[Nm]
Definition: iob.cpp:241
int read_digital_input(char *dinput)
read_digital_input, non-applicable bits are nop
Definition: iob.cpp:714
int write_angle_offset(int id, double offset)
write offset value for joint[rad]
Definition: iob.cpp:521
int write_force_offset(int id, double *offsets)
write offset values for force sensor output
Definition: iob.cpp:472
int length_digital_input()
get_digital_input_length
Definition: iob.cpp:719
int set_number_of_force_sensors(int num)
set the number of force sensors
Definition: iob.cpp:101
int write_command_velocity(int id, double vel)
write command angular velocity[rad/s]
Definition: iob.cpp:365
int read_command_angle(int id, double *angle)
read command angle[rad]
Definition: iob.cpp:246
int set_number_of_accelerometers(int num)
set the number of accelerometers
Definition: iob.cpp:131
int read_power(double *v, double *a)
read status of power source
Definition: iob.cpp:563
int read_extra_servo_state(int id, int *state)
read extra servo states
Definition: iob.cpp:692
long get_signal_period()
get the period of signals issued by wait_for_iob_signal()
Definition: iob.cpp:703
int write_attitude_sensor_offset(int id, double *offset)
Definition: iob.cpp:480
int read_force_offset(int id, double *offsets)
read offset values for force sensor output
Definition: iob.cpp:464
int read_power_command(int id, int *com)
turn on/off power supply for motor driver
Definition: iob.cpp:172
int write_gyro_sensor_offset(int id, double *offset)
write offset values for gyro sensor output
Definition: iob.cpp:440
unsigned long long read_iob_frame()
Definition: iob.cpp:551
int number_of_force_sensors()
get the number of force sensors
Definition: iob.cpp:70
size_t length_of_extra_servo_state(int id)
get length of extra servo states
Definition: iob.cpp:687


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