Defines |
#define | CHECK_ACCELEROMETER_ID(id) if ((id) < 0 || (id) >= number_of_accelerometers()) return E_ID |
#define | CHECK_ATTITUDE_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_attitude_sensors()) return E_ID |
#define | CHECK_FORCE_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_force_sensors()) return E_ID |
#define | CHECK_GYRO_SENSOR_ID(id) if ((id) < 0 || (id) >= number_of_gyro_sensors()) return E_ID |
#define | CHECK_JOINT_ID(id) if ((id) < 0 || (id) >= number_of_joints()) return E_ID |
Functions |
int | close_iob (void) |
| close connection with joint servo process
|
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 | joint_calibration (int id, double angle) |
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
|
int | lock_iob () |
| lock access to 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
|
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 | 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_actual_torques (double *torques) |
| read array of current joint torques[Nm]
|
int | read_actual_velocities (double *vels) |
| read actual angular velocities[rad/s]
|
int | read_actual_velocity (int id, double *vel) |
| read actual angular velocity[rad/s]
|
int | read_angle_offset (int id, double *angle) |
| read offset value for joint[rad]
|
int | read_attitude_sensor (int id, double *att) |
| read output of attitude sensor
|
int | read_calib_state (int id, int *s) |
| read callibration state of joint
|
int | read_command_angle (int id, double *angle) |
| read command angle[rad]
|
int | read_command_angles (double *angles) |
| read array of command angles[rad]
|
int | read_command_torque (int id, double *torque) |
| read command torque[Nm]
|
int | read_command_torques (double *torques) |
| read array of command torques[Nm]
|
int | read_command_velocities (double *vels) |
| read command angular velocities[rad/s]
|
int | read_command_velocity (int id, double *vel) |
| read command angular velocity[rad/s]
|
int | read_control_mode (int id, joint_control_mode *s) |
| read joint control mode
|
int | read_current (int id, double *mcurrent) |
int | read_current_limit (int id, double *v) |
int | read_currents (double *currents) |
int | read_dgain (int id, double *gain) |
| read D gain[Nm/(rad/s)]
|
int | read_digital_input (char *dinput) |
| read_digital_input, non-applicable bits are nop
|
int | read_digital_output (char *doutput) |
| read_digital_output, non-applicable bits are nop
|
int | read_driver_temperature (int id, unsigned char *v) |
| read temperature of motor driver[Celsius]
|
int | read_encoder_pulse (int id, double *ec) |
int | read_extra_servo_state (int id, int *state) |
| read extra servo states
|
int | read_force_offset (int id, double *offsets) |
| read offset values for force sensor output
|
int | read_force_sensor (int id, double *forces) |
| read output of force sensor
|
int | read_gauges (double *gauges) |
int | read_gear_ratio (int id, double *gr) |
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
|
unsigned long long | read_iob_frame () |
int | read_limit_angle (int id, double *angle) |
int | read_llimit_angle (int id, double *angle) |
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]
|
int | read_power (double *voltage, double *current) |
| read status of power source
|
int | read_power_command (int id, int *com) |
| turn on/off power supply for motor driver
|
int | read_power_state (int id, int *s) |
| read power status of motor driver
|
int | read_servo_alarm (int id, int *a) |
| read servo alarms
|
int | read_servo_state (int id, int *s) |
| read servo status
|
int | read_temperature (int id, double *v) |
| read thermometer
|
int | read_torque_const (int id, double *tc) |
int | read_torque_limit (int id, double *limit) |
int | read_touch_sensors (unsigned short *onoff) |
int | read_ulimit_angle (int id, double *angle) |
int | reset_body (void) |
int | set_number_of_accelerometers (int num) |
| set the number of accelerometers
|
int | set_number_of_attitude_sensors (int num) |
int | set_number_of_force_sensors (int num) |
| set the number of force sensors
|
int | set_number_of_gyro_sensors (int num) |
| set the number of gyro sensors
|
int | set_number_of_joints (int num) |
| set the number of joints
|
int | set_signal_period (long period_ns) |
| set the period of signals issued by wait_for_iob_signal()
|
void | timespec_add_ns (timespec *ts, long ns) |
double | timespec_compare (timespec *ts1, timespec *ts2) |
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
|
int | write_angle_offset (int id, double angle) |
| write offset value for joint[rad]
|
int | write_attitude_sensor_offset (int id, double *offset) |
int | write_command_angle (int id, double angle) |
| write command angle[rad]
|
int | write_command_angles (const double *angles) |
| write array of command angles[rad]
|
int | write_command_torque (int id, double torque) |
| write command torque[Nm]
|
int | write_command_torques (const double *torques) |
| write array of command torques[Nm]
|
int | write_command_velocities (const double *vels) |
| write command angular velocities[rad/s]
|
int | write_command_velocity (int id, double vel) |
| write command angular velocity[rad/s]
|
int | write_control_mode (int id, joint_control_mode s) |
| write joint control mode
|
int | write_dgain (int id, double gain) |
| write D gain[Nm/(rad/s)]
|
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 *mask) |
| write_digital_output, non-applicable bits are nop
|
int | write_dio (unsigned short buf) |
int | write_force_offset (int id, double *offsets) |
| write offset values for force sensor output
|
int | write_gyro_sensor_offset (int id, double *offset) |
| write offset values for gyro sensor output
|
int | write_pgain (int id, double gain) |
| write P gain[Nm/rad]
|
int | write_power_command (int id, int com) |
| turn on/off power supply for motor driver
|
int | write_servo (int id, int com) |
| turn on/off joint servo
|
Variables |
static std::vector
< std::vector< double > > | accel_offset |
static std::vector
< std::vector< double > > | accelerometers |
static std::vector
< std::vector< double > > | attitude_sensors |
static std::vector< double > | command |
static std::vector
< std::vector< double > > | force_offset |
static std::vector
< std::vector< double > > | forces |
static int | frame = 0 |
static long | g_period_ns = 5000000 |
static timespec | g_ts |
static std::vector
< std::vector< double > > | gyro_offset |
static std::vector
< std::vector< double > > | gyros |
static bool | isLocked = false |
static std::vector< int > | power |
static std::vector< int > | servo |