33 #define SS_OVER_VOLTAGE 0x001 34 #define SS_OVER_LOAD 0x002 35 #define SS_OVER_VELOCITY 0x004 36 #define SS_OVER_CURRENT 0x008 38 #define SS_OVER_HEAT 0x010 39 #define SS_TORQUE_LIMIT 0x020 40 #define SS_VELOCITY_LIMIT 0x040 41 #define SS_FORWARD_LIMIT 0x080 43 #define SS_REVERSE_LIMIT 0x100 44 #define SS_POSITION_ERROR 0x200 45 #define SS_ENCODER_ERROR 0x400 46 #define SS_OTHER 0x800 48 #define SS_RESERVED1 0x1000 49 #define SS_RESERVED2 0x2000 50 #define SS_RESERVED3 0x4000 51 #define SS_EMERGENCY 0x8000 55 #define JID_INVALID -2 66 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 583 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 2 592 int number_of_batteries();
602 int read_battery(
int id,
double *v,
double *
a,
double *
b);
608 int number_of_thermometers();
613 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 3 624 int write_command_acceleration(
int id,
double acc);
632 int write_command_accelerations(
const double *accs);
640 int write_joint_inertia(
int id,
double mn);
648 int write_joint_inertias(
const double *mns);
656 int read_pd_controller_torques(
double *torques);
663 int write_disturbance_observer(
int com);
670 int write_disturbance_observer_gain(
double gain);
674 #if defined(ROBOT_IOB_VERSION) && ROBOT_IOB_VERSION >= 4 685 int read_torque_pgain(
int id,
double *gain);
693 int write_torque_pgain(
int id,
double gain);
701 int read_torque_dgain(
int id,
double *gain);
709 int write_torque_dgain(
int id,
double gain);
int read_gyro_sensor(int id, double *rates)
read output of gyro sensor
int read_pgain(int id, double *gain)
read P gain[Nm/rad]
int read_force_sensor(int id, double *forces)
read output of force sensor
int unlock_iob()
unlock access to iob
static std::vector< std::vector< double > > forces
int read_actual_velocities(double *vels)
read actual angular velocities[rad/s]
int read_servo_alarm(int id, int *a)
read servo alarms
int write_accelerometer_offset(int id, double *offset)
write offset values for accelerometer output
int read_power_state(int id, int *s)
read power status of motor driver
int number_of_joints()
get the number of joints
int read_angle_offset(int id, double *offset)
read offset value for joint[rad]
int number_of_gyro_sensors()
get the number of gyro sensors
int number_of_accelerometers()
get the number of accelerometers
int wait_for_iob_signal()
wait until iob signal is issued
int read_servo_state(int id, int *s)
read servo status
int read_command_angles(double *angles)
read array of command angles[rad]
int close_iob(void)
close connection with joint servo process
int set_signal_period(long period_ns)
set the period of signals issued by wait_for_iob_signal()
int write_control_mode(int id, joint_control_mode s)
write joint control mode
int read_temperature(int id, double *v)
read thermometer
int open_iob(void)
open connection with joint servo process
int read_gyro_sensor_offset(int id, double *offset)
read offset values for gyro sensor output
int write_servo(int id, int com)
turn on/off joint servo
int write_command_angle(int id, double angle)
write command angle[rad]
int read_command_torques(double *torques)
read array of command torques[Nm]
int read_actual_torques(double *torques)
read array of current joint torques[Nm]
int read_actual_angle(int id, double *angle)
read current joint angle[rad]
int set_number_of_gyro_sensors(int num)
set the number of gyro sensors
int read_command_velocity(int id, double *vel)
read command angular velocity[rad/s]
int read_accelerometer(int id, double *accels)
read output of accelerometer
int read_command_torque(int id, double *torque)
read command torque[Nm]
int write_dgain(int id, double gain)
write D gain[Nm/(rad/s)]
int read_driver_temperature(int id, unsigned char *v)
read temperature of motor driver[Celsius]
int set_number_of_joints(int num)
set the number of joints
int write_pgain(int id, double gain)
write P gain[Nm/rad]
int lock_iob()
lock access to iob
int read_attitude_sensor(int id, double *att)
read output of attitude sensor
int read_command_velocities(double *vels)
read command angular velocities[rad/s]
int read_digital_output(char *doutput)
read_digital_output, non-applicable bits are nop
int length_digital_output()
get_digital_output_length
int write_command_angles(const double *angles)
write array of command angles[rad]
int read_control_mode(int id, joint_control_mode *s)
read joint control mode
int write_command_torque(int id, double torque)
write command torque[Nm]
int read_lock_owner(pid_t *pid)
read id of the process whic is locking access to iob
int write_digital_output_with_mask(const char *doutput, const char *dmask)
write_digital_output, non-applicable bits are nop
int write_command_velocities(const double *vels)
write command angular velocities[rad/s]
int read_calib_state(int id, int *s)
read callibration state of joint
int read_actual_velocity(int id, double *vel)
read actual angular velocity[rad/s]
int read_accelerometer_offset(int id, double *offset)
read offset values for accelerometer output
int read_dgain(int id, double *gain)
read D gain[Nm/(rad/s)]
int number_of_attitude_sensors()
get the number of attitude sensors
int write_power_command(int id, int com)
turn on/off power supply for motor driver
int write_digital_output(const char *doutput)
write_digital_output, non-applicable bits are nop
int read_actual_angles(double *angles)
read array of current joint angles[rad]
int initializeJointAngle(const char *name, const char *option)
initialize joint angle
int write_command_torques(const double *torques)
write array of command torques[Nm]
int read_digital_input(char *dinput)
read_digital_input, non-applicable bits are nop
int write_angle_offset(int id, double offset)
write offset value for joint[rad]
int write_force_offset(int id, double *offsets)
write offset values for force sensor output
int length_digital_input()
get_digital_input_length
int set_number_of_force_sensors(int num)
set the number of force sensors
int write_command_velocity(int id, double vel)
write command angular velocity[rad/s]
int read_command_angle(int id, double *angle)
read command angle[rad]
int set_number_of_accelerometers(int num)
set the number of accelerometers
int read_power(double *v, double *a)
read status of power source
int read_extra_servo_state(int id, int *state)
read extra servo states
long get_signal_period()
get the period of signals issued by wait_for_iob_signal()
int write_attitude_sensor_offset(int id, double *offset)
int read_force_offset(int id, double *offsets)
read offset values for force sensor output
int read_power_command(int id, int *com)
turn on/off power supply for motor driver
int write_gyro_sensor_offset(int id, double *offset)
write offset values for gyro sensor output
unsigned long long read_iob_frame()
int number_of_force_sensors()
get the number of force sensors
size_t length_of_extra_servo_state(int id)
get length of extra servo states