Defines | Enumerations
iob.h File Reference

abstract interface for the robot hardware More...

This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Defines

#define JID_ALL   -1
#define JID_INVALID   -2
#define MASK_OFF   1
#define MASK_ON   0
#define OFF   0
#define ON   1
return value
#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

Detailed Description

abstract interface for the robot hardware

Definition in file iob.h.


Define Documentation

#define E_ID   -1

invalid joint(or sensor) id

Definition at line 26 of file iob.h.

#define JID_ALL   -1

Definition at line 54 of file iob.h.

#define JID_INVALID   -2

Definition at line 55 of file iob.h.

#define MASK_OFF   1

Definition at line 12 of file iob.h.

#define MASK_ON   0

Definition at line 11 of file iob.h.

#define OFF   0

Definition at line 9 of file iob.h.

#define ON   1

Definition at line 8 of file iob.h.

#define SS_EMERGENCY   0x8000

Definition at line 51 of file iob.h.

#define SS_ENCODER_ERROR   0x400

Definition at line 45 of file iob.h.

#define SS_FORWARD_LIMIT   0x080

Definition at line 41 of file iob.h.

#define SS_OTHER   0x800

Definition at line 46 of file iob.h.

#define SS_OVER_CURRENT   0x008

Definition at line 36 of file iob.h.

#define SS_OVER_HEAT   0x010

Definition at line 38 of file iob.h.

#define SS_OVER_LOAD   0x002

Definition at line 34 of file iob.h.

#define SS_OVER_VELOCITY   0x004

Definition at line 35 of file iob.h.

#define SS_OVER_VOLTAGE   0x001

Definition at line 33 of file iob.h.

#define SS_POSITION_ERROR   0x200

Definition at line 44 of file iob.h.

#define SS_RESERVED1   0x1000

Definition at line 48 of file iob.h.

#define SS_RESERVED2   0x2000

Definition at line 49 of file iob.h.

#define SS_RESERVED3   0x4000

Definition at line 50 of file iob.h.

#define SS_REVERSE_LIMIT   0x100

Definition at line 43 of file iob.h.

#define SS_TORQUE_LIMIT   0x020

Definition at line 39 of file iob.h.

#define SS_VELOCITY_LIMIT   0x040

Definition at line 40 of file iob.h.


Enumeration Type Documentation

Enumerator:
JCM_FREE 

free

JCM_POSITION 

position control

JCM_TORQUE 

torque control

JCM_VELOCITY 

velocity control

JCM_NUM 

Definition at line 61 of file iob.h.


Function Documentation

close connection with joint servo process

Return values:
TRUEclosed successfully
FALSEotherwise

Definition at line 413 of file iob.cpp.

get the period of signals issued by wait_for_iob_signal()

Returns:
the period of signals[ns]

Definition at line 703 of file iob.cpp.

int initializeJointAngle ( const char *  name,
const char *  option 
)

initialize joint angle

Parameters:
namejoint name, part name or "all"
optionstring of joint angle initialization
Returns:
TRUE if initialized successfully, FALSE otherwise

Definition at line 708 of file iob.cpp.

get_digital_input_length

Returns:
length of digital input in bytes

Definition at line 719 of file iob.cpp.

get_digital_output_length

Returns:
length of digital output in bytes

Definition at line 734 of file iob.cpp.

get length of extra servo states

Parameters:
idjoint id
Returns:
length of extra servo states

Definition at line 687 of file iob.cpp.

lock access to iob

Return values:
TRUEiob is locked successfully
FALSEsome other process is locking iob

Definition at line 493 of file iob.cpp.

get the number of accelerometers

Returns:
the number of accelerometers

Definition at line 80 of file iob.cpp.

get the number of attitude sensors

Returns:
the number of attitude sensors

Definition at line 85 of file iob.cpp.

get the number of force sensors

Returns:
the number of force sensors

Definition at line 70 of file iob.cpp.

get the number of gyro sensors

Returns:
the number of gyro sensors

Definition at line 75 of file iob.cpp.

get the number of joints

Returns:
the number of joints

Definition at line 65 of file iob.cpp.

Returns:
the number of substeps

Definition at line 558 of file iob.cpp.

int open_iob ( void  )

open connection with joint servo process

Return values:
TRUEopened successfully
FALSEotherwise

Definition at line 401 of file iob.cpp.

int read_accelerometer ( int  id,
double *  accels 
)

read output of accelerometer

Parameters:
idaccelerometer id
accelsaccelerations [m/s^2], length of array must be 3
Returns:
TRUE or E_ID

Definition at line 315 of file iob.cpp.

int read_accelerometer_offset ( int  id,
double *  offset 
)

read offset values for accelerometer output

Parameters:
idaccelerometer id
offsetoffset values[rad/s^2], length of array must be 3.
Return values:
TRUEoffset values are read successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 448 of file iob.cpp.

int read_actual_angle ( int  id,
double *  angle 
)

read current joint angle[rad]

Parameters:
idjoint id
angleactual joint angle[rad]
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 206 of file iob.cpp.

int read_actual_angles ( double *  angles)

read array of current joint angles[rad]

Parameters:
anglesarray of joint angle[rad], length of array must be equal to number_of_joints()
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 213 of file iob.cpp.

int read_actual_torques ( double *  torques)

read array of current joint torques[Nm]

Parameters:
torquesarray of actual joint torque[Nm], length of array must be equal to number_of_joints()
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 221 of file iob.cpp.

int read_actual_velocities ( double *  vels)

read actual angular velocities[rad/s]

Parameters:
velsarray of angular velocity [rad/s]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 370 of file iob.cpp.

int read_actual_velocity ( int  id,
double *  vel 
)

read actual angular velocity[rad/s]

Parameters:
idjoint id
velangular velocity [rad/s]
Returns:
TRUE or E_ID

Definition at line 355 of file iob.cpp.

int read_angle_offset ( int  id,
double *  offset 
)

read offset value for joint[rad]

Parameters:
idjoint id
offsetoffset value[rad]
Return values:
TRUEoffset value is read successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 516 of file iob.cpp.

int read_attitude_sensor ( int  id,
double *  att 
)

read output of attitude sensor

Parameters:
idattitude sensor id
attroll-pitch-yaw angle[rad], length of array must be 3
Return values:
TRUEsensor values are read successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 330 of file iob.cpp.

int read_calib_state ( int  id,
int s 
)

read callibration state of joint

Parameters:
idjoint id
sTRUE if calibration is already done, FALSE otherwise
Return values:
TRUEcalibration status is read successfully
E_IDinvalid joint id is specified
FALSEthis function is not supported

Definition at line 485 of file iob.cpp.

int read_command_angle ( int  id,
double *  angle 
)

read command angle[rad]

Parameters:
idjoint id
anglecommand joint angle[rad]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 246 of file iob.cpp.

int read_command_angles ( double *  angles)

read array of command angles[rad]

Parameters:
anglesarray of joint angles[rad], length of array must equal to DOF
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 260 of file iob.cpp.

int read_command_torque ( int  id,
double *  torque 
)

read command torque[Nm]

Parameters:
idjoint id
torquejoint torque[Nm]
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 226 of file iob.cpp.

int read_command_torques ( double *  torques)

read array of command torques[Nm]

Parameters:
torquesarray of command torques[Nm]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 236 of file iob.cpp.

int read_command_velocities ( double *  vels)

read command angular velocities[rad/s]

Parameters:
velsarray of angular velocity [rad/s]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 375 of file iob.cpp.

int read_command_velocity ( int  id,
double *  vel 
)

read command angular velocity[rad/s]

Parameters:
idjoint id
velangular velocity [rad/s]
Returns:
TRUE or E_ID

Definition at line 360 of file iob.cpp.

read joint control mode

Parameters:
idjoint id
sjoint control mode
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 193 of file iob.cpp.

int read_dgain ( int  id,
double *  gain 
)

read D gain[Nm/(rad/s)]

Parameters:
idjoint id
gainD gain[Nm/(rad/s)]
Returns:
TRUE or E_ID

Definition at line 286 of file iob.cpp.

int read_digital_input ( char *  dinput)

read_digital_input, non-applicable bits are nop

Parameters:
dinputdigital input from environment
Returns:
TRUE if applicable, FALSE otherwise

Definition at line 714 of file iob.cpp.

int read_digital_output ( char *  doutput)

read_digital_output, non-applicable bits are nop

Parameters:
doutputdigital output to environment
Returns:
TRUE if applicable, FALSE otherwise

Definition at line 739 of file iob.cpp.

int read_driver_temperature ( int  id,
unsigned char *  v 
)

read temperature of motor driver[Celsius]

Parameters:
idjoint id
vtemperature[Celsius]
Return values:
TRUEtemperature is read successfully
E_IDinvalid joint id is specified
FALSEthis function is not supported

Definition at line 649 of file iob.cpp.

int read_extra_servo_state ( int  id,
int state 
)

read extra servo states

Parameters:
idjoint id
statearray of int where extra servo states are stored
Returns:
TRUE if read successfully, FALSE otherwise

Definition at line 692 of file iob.cpp.

int read_force_offset ( int  id,
double *  offsets 
)

read offset values for force sensor output

Parameters:
idforce/torque sensor id
offsetsoffset values[N][Nm], length of array must be 6.
Return values:
TRUEoffset values are read successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 464 of file iob.cpp.

int read_force_sensor ( int  id,
double *  forces 
)

read output of force sensor

Parameters:
idForce Sensor id
forcesarray of forces[N] and moments[Nm], length of array must be 6
Returns:
TRUE or E_ID

Definition at line 296 of file iob.cpp.

int read_gyro_sensor ( int  id,
double *  rates 
)

read output of gyro sensor

Parameters:
idgyro sensor id
ratesangular velocities [rad/s], length of array must be 3
Returns:
TRUE or E_ID

Definition at line 305 of file iob.cpp.

int read_gyro_sensor_offset ( int  id,
double *  offset 
)

read offset values for gyro sensor output

Parameters:
idgyro sensor id
offsetoffset values[rad/s], length of array must be 3.
Return values:
TRUEoffset values are read successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 432 of file iob.cpp.

unsigned long long read_iob_frame ( )

Definition at line 551 of file iob.cpp.

read id of the process whic is locking access to iob

Definition at line 506 of file iob.cpp.

int read_pgain ( int  id,
double *  gain 
)

read P gain[Nm/rad]

Parameters:
idjoint id
gainP gain[Nm/rad]
Returns:
TRUE or E_ID

Definition at line 276 of file iob.cpp.

int read_power ( double *  v,
double *  a 
)

read status of power source

Parameters:
vvoltage[V]
acurrent[A]
Returns:
TRUE or FALSE

Definition at line 563 of file iob.cpp.

int read_power_command ( int  id,
int com 
)

turn on/off power supply for motor driver

Parameters:
idjoint id
comON/OFF
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 172 of file iob.cpp.

int read_power_state ( int  id,
int s 
)

read power status of motor driver

Parameters:
idjoint id
sON or OFF is returned
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 158 of file iob.cpp.

int read_servo_alarm ( int  id,
int a 
)

read servo alarms

Parameters:
idjoint id
aservo alarms
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 186 of file iob.cpp.

int read_servo_state ( int  id,
int s 
)

read servo status

Parameters:
idjoint id
sON/OFF
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 179 of file iob.cpp.

int read_temperature ( int  id,
double *  v 
)

read thermometer

Parameters:
idid of thermometer
vtemperature[Celsius]
Return values:
TRUEtemperature is read successfully
E_IDinvalid thermometer id is specified
FALSEthis function is not supported

Definition at line 385 of file iob.cpp.

Definition at line 419 of file iob.cpp.

set the number of accelerometers

Parameters:
numthe number of accelerometers
Returns:
TRUE if the number of accelerometers is set, FALSE otherwise

Definition at line 131 of file iob.cpp.

set the number of force sensors

Parameters:
numthe number of force sensors
Returns:
TRUE if the number of force sensors is set, FALSE otherwise

Definition at line 101 of file iob.cpp.

set the number of gyro sensors

Parameters:
numthe number of gyro sensors
Returns:
TRUE if the number of gyro sensors is set, FALSE otherwise

Definition at line 116 of file iob.cpp.

set the number of joints

Parameters:
numthe number of joints
Returns:
TRUE if the number of joints is set, FALSE otherwise

Definition at line 90 of file iob.cpp.

int set_signal_period ( long  period_ns)

set the period of signals issued by wait_for_iob_signal()

Parameters:
period_nsthe period of signals[ns]
Returns:
TRUE if set successfully, FALSE otherwise

Definition at line 697 of file iob.cpp.

unlock access to iob

Definition at line 500 of file iob.cpp.

wait until iob signal is issued

Returns:
TRUE if signal is received successfully, FALSE otherwise

Definition at line 671 of file iob.cpp.

int write_accelerometer_offset ( int  id,
double *  offset 
)

write offset values for accelerometer output

Parameters:
idaccelerometer id
offsetoffset values[rad/s^2], length of array must be 3.
Return values:
TRUEoffset values are written successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 456 of file iob.cpp.

int write_angle_offset ( int  id,
double  offset 
)

write offset value for joint[rad]

Parameters:
idjoint id
offsetoffset value[rad]
Return values:
TRUEoffset values are written successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 521 of file iob.cpp.

int write_attitude_sensor_offset ( int  id,
double *  offset 
)

Definition at line 480 of file iob.cpp.

int write_command_angle ( int  id,
double  angle 
)

write command angle[rad]

Parameters:
idjoint id
anglecommand joint angle[rad]
Returns:
TRUE or E_ID

Definition at line 253 of file iob.cpp.

int write_command_angles ( const double *  angles)

write array of command angles[rad]

Parameters:
anglesarray of joint angles[rad], length of array must equal to DOF
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 268 of file iob.cpp.

int write_command_torque ( int  id,
double  torque 
)

write command torque[Nm]

Parameters:
idjoint id
torquejoint torque[Nm]
Returns:
TRUE if this function is supported, FALSE otherwise

Definition at line 231 of file iob.cpp.

int write_command_torques ( const double *  torques)

write array of command torques[Nm]

Parameters:
torquesarray of command torques[Nm]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 241 of file iob.cpp.

int write_command_velocities ( const double *  vels)

write command angular velocities[rad/s]

Parameters:
velsarray of angular velocity [rad/s]
Return values:
TRUEthis function is supported
FALSEotherwise

Definition at line 380 of file iob.cpp.

int write_command_velocity ( int  id,
double  vel 
)

write command angular velocity[rad/s]

Parameters:
idjoint id
velangular velocity [rad/s]
Returns:
TRUE or E_ID

Definition at line 365 of file iob.cpp.

write joint control mode

Parameters:
idjoint id
sjoint control mode
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 200 of file iob.cpp.

int write_dgain ( int  id,
double  gain 
)

write D gain[Nm/(rad/s)]

Parameters:
idjoint id
gainD gain[Nm/(rad/s)]
Returns:
TRUE or E_ID

Definition at line 291 of file iob.cpp.

int write_digital_output ( const char *  doutput)

write_digital_output, non-applicable bits are nop

Parameters:
doutputset digital output to environment
Returns:
TRUE if applicable, FALSE otherwise

Definition at line 724 of file iob.cpp.

int write_digital_output_with_mask ( const char *  doutput,
const char *  dmask 
)

write_digital_output, non-applicable bits are nop

Parameters:
doutputset digital output to environment
maskbinary vector which selects output to be set
Returns:
TRUE if applicable, FALSE otherwise

Definition at line 729 of file iob.cpp.

int write_force_offset ( int  id,
double *  offsets 
)

write offset values for force sensor output

Parameters:
idforce/torque id
offsetsoffset values[N][Nm], length of array must be 6.
Return values:
TRUEoffset values are written successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 472 of file iob.cpp.

int write_gyro_sensor_offset ( int  id,
double *  offset 
)

write offset values for gyro sensor output

Parameters:
idgyro sensor id
offsetoffset values[rad/s], length of array must be 3.
Return values:
TRUEoffset values are written successfully
E_IDinvalid id is specified
FALSEthis function is not supported

Definition at line 440 of file iob.cpp.

int write_pgain ( int  id,
double  gain 
)

write P gain[Nm/rad]

Parameters:
idjoint id
gainP gain[Nm/rad]
Returns:
TRUE or E_ID

Definition at line 281 of file iob.cpp.

int write_power_command ( int  id,
int  com 
)

turn on/off power supply for motor driver

Parameters:
idjoint id
comON/OFF
Return values:
TRUEthis function is supported
E_IDinvalid joint id is specified
FALSEotherwise

Definition at line 165 of file iob.cpp.

int write_servo ( int  id,
int  com 
)

turn on/off joint servo

Parameters:
idjoint id
comON/OFF
Returns:
TRUE if this function is supported, FALSE otherwise

Definition at line 390 of file iob.cpp.



hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:19