|
Basic RT components and utilities
315.12.1
|
abstract interface for the robot hardware More...
Defines | |
| #define | ON 1 |
| #define | OFF 0 |
| #define | MASK_ON 0 |
| #define | MASK_OFF 1 |
| #define | JID_ALL -1 |
| #define | JID_INVALID -2 |
return value | |
| #define | FALSE 0 |
| #define | TRUE 1 |
| #define | E_ID -1 |
| invalid joint(or sensor) id | |
servo alarm | |
| #define | SS_OVER_VOLTAGE 0x001 |
| #define | SS_OVER_LOAD 0x002 |
| #define | SS_OVER_VELOCITY 0x004 |
| #define | SS_OVER_CURRENT 0x008 |
| #define | SS_OVER_HEAT 0x010 |
| #define | SS_TORQUE_LIMIT 0x020 |
| #define | SS_VELOCITY_LIMIT 0x040 |
| #define | SS_FORWARD_LIMIT 0x080 |
| #define | SS_REVERSE_LIMIT 0x100 |
| #define | SS_POSITION_ERROR 0x200 |
| #define | SS_ENCODER_ERROR 0x400 |
| #define | SS_OTHER 0x800 |
| #define | SS_RESERVED1 0x1000 |
| #define | SS_RESERVED2 0x2000 |
| #define | SS_RESERVED3 0x4000 |
| #define | SS_EMERGENCY 0x8000 |
Enumerations | |
| enum | joint_control_mode { JCM_FREE, JCM_POSITION, JCM_TORQUE, JCM_VELOCITY, JCM_NUM } |
Functions | |
the number of joints and sensors | |
| int | number_of_joints () |
| get the number of joints | |
| int | set_number_of_joints (int num) |
| set the number of joints | |
| int | number_of_force_sensors () |
| get the number of force sensors | |
| int | set_number_of_force_sensors (int num) |
| set the number of force sensors | |
| int | number_of_gyro_sensors () |
| get the number of gyro sensors | |
| int | set_number_of_gyro_sensors (int num) |
| set the number of gyro sensors | |
| int | number_of_accelerometers () |
| get the number of accelerometers | |
| int | set_number_of_accelerometers (int num) |
| set the number of accelerometers | |
| int | number_of_attitude_sensors () |
| get the number of attitude sensors | |
joint angle | |
| int | read_actual_angle (int id, double *angle) |
| read current joint angle[rad] | |
| int | read_actual_angles (double *angles) |
| read array of current joint angles[rad] | |
| int | read_angle_offset (int id, double *offset) |
| read offset value for joint[rad] | |
| int | write_angle_offset (int id, double offset) |
| write offset value for joint[rad] | |
| int | read_power_state (int id, int *s) |
| read power status of motor driver | |
| int | write_power_command (int id, int com) |
| turn on/off power supply for motor driver | |
| int | read_power_command (int id, int *com) |
| turn on/off power supply for motor driver | |
| int | read_servo_state (int id, int *s) |
| read servo status | |
| int | read_servo_alarm (int id, int *a) |
| read servo alarms | |
| int | read_control_mode (int id, joint_control_mode *s) |
| read joint control mode | |
| int | write_control_mode (int id, joint_control_mode s) |
| write joint control mode | |
| int | read_actual_torques (double *torques) |
| read array of current joint torques[Nm] | |
| int | read_command_torque (int id, double *torque) |
| read command torque[Nm] | |
| int | write_command_torque (int id, double torque) |
| write command torque[Nm] | |
| int | read_command_torques (double *torques) |
| read array of command torques[Nm] | |
| int | write_command_torques (const double *torques) |
| write array of command torques[Nm] | |
| int | read_command_angle (int id, double *angle) |
| read command angle[rad] | |
| int | write_command_angle (int id, double angle) |
| write command angle[rad] | |
| int | read_command_angles (double *angles) |
| read array of command angles[rad] | |
| int | write_command_angles (const double *angles) |
| write array of command angles[rad] | |
| int | read_pgain (int id, double *gain) |
| read P gain[Nm/rad] | |
| int | write_pgain (int id, double gain) |
| write P gain[Nm/rad] | |
| int | read_dgain (int id, double *gain) |
| read D gain[Nm/(rad/s)] | |
| int | write_dgain (int id, double gain) |
| write D gain[Nm/(rad/s)] | |
| int | read_actual_velocity (int id, double *vel) |
| read actual angular velocity[rad/s] | |
| int | read_command_velocity (int id, double *vel) |
| read command angular velocity[rad/s] | |
| int | write_command_velocity (int id, double vel) |
| write command angular velocity[rad/s] | |
| int | read_actual_velocities (double *vels) |
| read actual angular velocities[rad/s] | |
| int | read_command_velocities (double *vels) |
| read command angular velocities[rad/s] | |
| int | write_command_velocities (const double *vels) |
| write command angular velocities[rad/s] | |
| int | write_servo (int id, int com) |
| turn on/off joint servo | |
| int | read_driver_temperature (int id, unsigned char *v) |
| read temperature of motor driver[Celsius] | |
| int | read_calib_state (int id, int *s) |
| read callibration state of joint | |
| size_t | length_of_extra_servo_state (int id) |
| get length of extra servo states | |
| int | read_extra_servo_state (int id, int *state) |
| read extra servo states | |
force sensor | |
| int | read_force_sensor (int id, double *forces) |
| read output of force sensor | |
| int | read_force_offset (int id, double *offsets) |
| read offset values for force sensor output | |
| int | write_force_offset (int id, double *offsets) |
| write offset values for force sensor output | |
gyro sensor | |
| int | read_gyro_sensor (int id, double *rates) |
| read output of gyro sensor | |
| int | read_gyro_sensor_offset (int id, double *offset) |
| read offset values for gyro sensor output | |
| int | write_gyro_sensor_offset (int id, double *offset) |
| write offset values for gyro sensor output | |
acceleromter | |
| int | read_accelerometer (int id, double *accels) |
| read output of accelerometer | |
| int | read_accelerometer_offset (int id, double *offset) |
| read offset values for accelerometer output | |
| int | write_accelerometer_offset (int id, double *offset) |
| write offset values for accelerometer output | |
attitude sensor | |
| int | read_attitude_sensor (int id, double *att) |
| read output of attitude sensor | |
| int | write_attitude_sensor_offset (int id, double *offset) |
power supply | |
| int | read_power (double *v, double *a) |
| read status of power source | |
thermometer | |
| int | read_temperature (int id, double *v) |
| read thermometer | |
open/close | |
| int | open_iob (void) |
| open connection with joint servo process | |
| int | close_iob (void) |
| close connection with joint servo process | |
| int | reset_body (void) |
| int | lock_iob () |
| lock access to iob | |
| int | unlock_iob () |
| unlock access to iob | |
| int | read_lock_owner (pid_t *pid) |
| read id of the process whic is locking access to iob | |
| unsigned long long | read_iob_frame () |
| int | number_of_substeps () |
| int | wait_for_iob_signal () |
| wait until iob signal is issued | |
| int | set_signal_period (long period_ns) |
| set the period of signals issued by wait_for_iob_signal() | |
| long | get_signal_period () |
| get the period of signals issued by wait_for_iob_signal() | |
| int | initializeJointAngle (const char *name, const char *option) |
| initialize joint angle | |
| int | read_digital_input (char *dinput) |
| read_digital_input, non-applicable bits are nop | |
| int | length_digital_input () |
| get_digital_input_length | |
| int | write_digital_output (const char *doutput) |
| write_digital_output, non-applicable bits are nop | |
| int | write_digital_output_with_mask (const char *doutput, const char *dmask) |
| write_digital_output, non-applicable bits are nop | |
| int | length_digital_output () |
| get_digital_output_length | |
| int | read_digital_output (char *doutput) |
| read_digital_output, non-applicable bits are nop | |
abstract interface for the robot hardware
| #define E_ID -1 |
invalid joint(or sensor) id
| #define FALSE 0 |
| #define JID_ALL -1 |
| #define JID_INVALID -2 |
| #define MASK_OFF 1 |
| #define MASK_ON 0 |
| #define OFF 0 |
| #define ON 1 |
| #define SS_EMERGENCY 0x8000 |
| #define SS_ENCODER_ERROR 0x400 |
| #define SS_FORWARD_LIMIT 0x080 |
| #define SS_OTHER 0x800 |
| #define SS_OVER_CURRENT 0x008 |
| #define SS_OVER_HEAT 0x010 |
| #define SS_OVER_LOAD 0x002 |
| #define SS_OVER_VELOCITY 0x004 |
| #define SS_OVER_VOLTAGE 0x001 |
| #define SS_POSITION_ERROR 0x200 |
| #define SS_RESERVED1 0x1000 |
| #define SS_RESERVED2 0x2000 |
| #define SS_RESERVED3 0x4000 |
| #define SS_REVERSE_LIMIT 0x100 |
| #define SS_TORQUE_LIMIT 0x020 |
| #define SS_VELOCITY_LIMIT 0x040 |
| #define TRUE 1 |
| enum joint_control_mode |
| int close_iob | ( | void | ) |
close connection with joint servo process
| TRUE | closed successfully |
| FALSE | otherwise |
| long get_signal_period | ( | ) |
get the period of signals issued by wait_for_iob_signal()
| int initializeJointAngle | ( | const char * | name, |
| const char * | option | ||
| ) |
initialize joint angle
| name | joint name, part name or "all" |
| option | string of joint angle initialization |
| int length_digital_input | ( | ) |
get_digital_input_length
| int length_digital_output | ( | ) |
get_digital_output_length
| size_t length_of_extra_servo_state | ( | int | id | ) |
get length of extra servo states
| id | joint id |
| int lock_iob | ( | ) |
lock access to iob
| TRUE | iob is locked successfully |
| FALSE | some other process is locking iob |
| int number_of_accelerometers | ( | ) |
get the number of accelerometers
| int number_of_attitude_sensors | ( | ) |
get the number of attitude sensors
| int number_of_force_sensors | ( | ) |
get the number of force sensors
| int number_of_gyro_sensors | ( | ) |
get the number of gyro sensors
| int number_of_joints | ( | ) |
get the number of joints
| int number_of_substeps | ( | ) |
| int open_iob | ( | void | ) |
open connection with joint servo process
| TRUE | opened successfully |
| FALSE | otherwise |
| int read_accelerometer | ( | int | id, |
| double * | accels | ||
| ) |
read output of accelerometer
| id | accelerometer id |
| accels | accelerations [m/s^2], length of array must be 3 |
| int read_accelerometer_offset | ( | int | id, |
| double * | offset | ||
| ) |
read offset values for accelerometer output
| id | accelerometer id |
| offset | offset values[rad/s^2], length of array must be 3. |
| TRUE | offset values are read successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int read_actual_angle | ( | int | id, |
| double * | angle | ||
| ) |
read current joint angle[rad]
| id | joint id |
| angle | actual joint angle[rad] |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_actual_angles | ( | double * | angles | ) |
read array of current joint angles[rad]
| angles | array of joint angle[rad], length of array must be equal to number_of_joints() |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_actual_torques | ( | double * | torques | ) |
read array of current joint torques[Nm]
| torques | array of actual joint torque[Nm], length of array must be equal to number_of_joints() |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_actual_velocities | ( | double * | vels | ) |
read actual angular velocities[rad/s]
| vels | array of angular velocity [rad/s] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_actual_velocity | ( | int | id, |
| double * | vel | ||
| ) |
read actual angular velocity[rad/s]
| id | joint id |
| vel | angular velocity [rad/s] |
| int read_angle_offset | ( | int | id, |
| double * | offset | ||
| ) |
read offset value for joint[rad]
| id | joint id |
| offset | offset value[rad] |
| TRUE | offset value is read successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int read_attitude_sensor | ( | int | id, |
| double * | att | ||
| ) |
read output of attitude sensor
| id | attitude sensor id |
| att | roll-pitch-yaw angle[rad], length of array must be 3 |
| TRUE | sensor values are read successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int read_calib_state | ( | int | id, |
| int * | s | ||
| ) |
read callibration state of joint
| id | joint id |
| s | TRUE if calibration is already done, FALSE otherwise |
| TRUE | calibration status is read successfully |
| E_ID | invalid joint id is specified |
| FALSE | this function is not supported |
| int read_command_angle | ( | int | id, |
| double * | angle | ||
| ) |
read command angle[rad]
| id | joint id |
| angle | command joint angle[rad] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_command_angles | ( | double * | angles | ) |
read array of command angles[rad]
| angles | array of joint angles[rad], length of array must equal to DOF |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_command_torque | ( | int | id, |
| double * | torque | ||
| ) |
read command torque[Nm]
| id | joint id |
| torque | joint torque[Nm] |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_command_torques | ( | double * | torques | ) |
read array of command torques[Nm]
| torques | array of command torques[Nm] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_command_velocities | ( | double * | vels | ) |
read command angular velocities[rad/s]
| vels | array of angular velocity [rad/s] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int read_command_velocity | ( | int | id, |
| double * | vel | ||
| ) |
read command angular velocity[rad/s]
| id | joint id |
| vel | angular velocity [rad/s] |
| int read_control_mode | ( | int | id, |
| joint_control_mode * | s | ||
| ) |
read joint control mode
| id | joint id |
| s | joint control mode |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_dgain | ( | int | id, |
| double * | gain | ||
| ) |
read D gain[Nm/(rad/s)]
| id | joint id |
| gain | D gain[Nm/(rad/s)] |
| int read_digital_input | ( | char * | dinput | ) |
read_digital_input, non-applicable bits are nop
| dinput | digital input from environment |
| int read_digital_output | ( | char * | doutput | ) |
read_digital_output, non-applicable bits are nop
| doutput | digital output to environment |
| int read_driver_temperature | ( | int | id, |
| unsigned char * | v | ||
| ) |
read temperature of motor driver[Celsius]
| id | joint id |
| v | temperature[Celsius] |
| TRUE | temperature is read successfully |
| E_ID | invalid joint id is specified |
| FALSE | this function is not supported |
| int read_extra_servo_state | ( | int | id, |
| int * | state | ||
| ) |
read extra servo states
| id | joint id |
| state | array of int where extra servo states are stored |
| int read_force_offset | ( | int | id, |
| double * | offsets | ||
| ) |
read offset values for force sensor output
| id | force/torque sensor id |
| offsets | offset values[N][Nm], length of array must be 6. |
| TRUE | offset values are read successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int read_force_sensor | ( | int | id, |
| double * | forces | ||
| ) |
read output of force sensor
| id | Force Sensor id |
| forces | array of forces[N] and moments[Nm], length of array must be 6 |
| int read_gyro_sensor | ( | int | id, |
| double * | rates | ||
| ) |
read output of gyro sensor
| id | gyro sensor id |
| rates | angular velocities [rad/s], length of array must be 3 |
| int read_gyro_sensor_offset | ( | int | id, |
| double * | offset | ||
| ) |
read offset values for gyro sensor output
| id | gyro sensor id |
| offset | offset values[rad/s], length of array must be 3. |
| TRUE | offset values are read successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| unsigned long long read_iob_frame | ( | ) |
| int read_lock_owner | ( | pid_t * | pid | ) |
read id of the process whic is locking access to iob
| int read_pgain | ( | int | id, |
| double * | gain | ||
| ) |
read P gain[Nm/rad]
| id | joint id |
| gain | P gain[Nm/rad] |
| int read_power | ( | double * | v, |
| double * | a | ||
| ) |
read status of power source
| v | voltage[V] |
| a | current[A] |
| int read_power_command | ( | int | id, |
| int * | com | ||
| ) |
turn on/off power supply for motor driver
| id | joint id |
| com | ON/OFF |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_power_state | ( | int | id, |
| int * | s | ||
| ) |
read power status of motor driver
| id | joint id |
| s | ON or OFF is returned |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_servo_alarm | ( | int | id, |
| int * | a | ||
| ) |
read servo alarms
| id | joint id |
| a | servo alarms |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_servo_state | ( | int | id, |
| int * | s | ||
| ) |
read servo status
| id | joint id |
| s | ON/OFF |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int read_temperature | ( | int | id, |
| double * | v | ||
| ) |
read thermometer
| id | id of thermometer |
| v | temperature[Celsius] |
| TRUE | temperature is read successfully |
| E_ID | invalid thermometer id is specified |
| FALSE | this function is not supported |
| int reset_body | ( | void | ) |
| int set_number_of_accelerometers | ( | int | num | ) |
set the number of accelerometers
| num | the number of accelerometers |
| int set_number_of_force_sensors | ( | int | num | ) |
set the number of force sensors
| num | the number of force sensors |
| int set_number_of_gyro_sensors | ( | int | num | ) |
set the number of gyro sensors
| num | the number of gyro sensors |
| int set_number_of_joints | ( | int | num | ) |
set the number of joints
| num | the number of joints |
| int set_signal_period | ( | long | period_ns | ) |
set the period of signals issued by wait_for_iob_signal()
| period_ns | the period of signals[ns] |
| int unlock_iob | ( | ) |
unlock access to iob
| int wait_for_iob_signal | ( | ) |
wait until iob signal is issued
| int write_accelerometer_offset | ( | int | id, |
| double * | offset | ||
| ) |
write offset values for accelerometer output
| id | accelerometer id |
| offset | offset values[rad/s^2], length of array must be 3. |
| TRUE | offset values are written successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int write_angle_offset | ( | int | id, |
| double | offset | ||
| ) |
write offset value for joint[rad]
| id | joint id |
| offset | offset value[rad] |
| TRUE | offset values are written successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int write_attitude_sensor_offset | ( | int | id, |
| double * | offset | ||
| ) |
| int write_command_angle | ( | int | id, |
| double | angle | ||
| ) |
write command angle[rad]
| id | joint id |
| angle | command joint angle[rad] |
| int write_command_angles | ( | const double * | angles | ) |
write array of command angles[rad]
| angles | array of joint angles[rad], length of array must equal to DOF |
| TRUE | this function is supported |
| FALSE | otherwise |
| int write_command_torque | ( | int | id, |
| double | torque | ||
| ) |
write command torque[Nm]
| id | joint id |
| torque | joint torque[Nm] |
| int write_command_torques | ( | const double * | torques | ) |
write array of command torques[Nm]
| torques | array of command torques[Nm] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int write_command_velocities | ( | const double * | vels | ) |
write command angular velocities[rad/s]
| vels | array of angular velocity [rad/s] |
| TRUE | this function is supported |
| FALSE | otherwise |
| int write_command_velocity | ( | int | id, |
| double | vel | ||
| ) |
write command angular velocity[rad/s]
| id | joint id |
| vel | angular velocity [rad/s] |
| int write_control_mode | ( | int | id, |
| joint_control_mode | s | ||
| ) |
write joint control mode
| id | joint id |
| s | joint control mode |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int write_dgain | ( | int | id, |
| double | gain | ||
| ) |
write D gain[Nm/(rad/s)]
| id | joint id |
| gain | D gain[Nm/(rad/s)] |
| int write_digital_output | ( | const char * | doutput | ) |
write_digital_output, non-applicable bits are nop
| doutput | set digital output to environment |
| int write_digital_output_with_mask | ( | const char * | doutput, |
| const char * | dmask | ||
| ) |
write_digital_output, non-applicable bits are nop
| doutput | set digital output to environment |
| mask | binary vector which selects output to be set |
| int write_force_offset | ( | int | id, |
| double * | offsets | ||
| ) |
write offset values for force sensor output
| id | force/torque id |
| offsets | offset values[N][Nm], length of array must be 6. |
| TRUE | offset values are written successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int write_gyro_sensor_offset | ( | int | id, |
| double * | offset | ||
| ) |
write offset values for gyro sensor output
| id | gyro sensor id |
| offset | offset values[rad/s], length of array must be 3. |
| TRUE | offset values are written successfully |
| E_ID | invalid id is specified |
| FALSE | this function is not supported |
| int write_pgain | ( | int | id, |
| double | gain | ||
| ) |
write P gain[Nm/rad]
| id | joint id |
| gain | P gain[Nm/rad] |
| int write_power_command | ( | int | id, |
| int | com | ||
| ) |
turn on/off power supply for motor driver
| id | joint id |
| com | ON/OFF |
| TRUE | this function is supported |
| E_ID | invalid joint id is specified |
| FALSE | otherwise |
| int write_servo | ( | int | id, |
| int | com | ||
| ) |
turn on/off joint servo
| id | joint id |
| com | ON/OFF |
1.7.6.1