Basic RT components and utilities  315.15.0
Macros | Enumerations
iob.h File Reference

abstract interface for the robot hardware More...

Macros

#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 More...
 
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 More...
 
int set_number_of_joints (int num)
 set the number of joints More...
 
int number_of_force_sensors ()
 get the number of force sensors More...
 
int set_number_of_force_sensors (int num)
 set the number of force sensors More...
 
int number_of_gyro_sensors ()
 get the number of gyro sensors More...
 
int set_number_of_gyro_sensors (int num)
 set the number of gyro sensors More...
 
int number_of_accelerometers ()
 get the number of accelerometers More...
 
int set_number_of_accelerometers (int num)
 set the number of accelerometers More...
 
int number_of_attitude_sensors ()
 get the number of attitude sensors More...
 
joint angle
int read_actual_angle (int id, double *angle)
 read current joint angle[rad] More...
 
int read_actual_angles (double *angles)
 read array of current joint angles[rad] More...
 
int read_angle_offset (int id, double *offset)
 read offset value for joint[rad] More...
 
int write_angle_offset (int id, double offset)
 write offset value for joint[rad] More...
 
int read_power_state (int id, int *s)
 read power status of motor driver More...
 
int write_power_command (int id, int com)
 turn on/off power supply for motor driver More...
 
int read_power_command (int id, int *com)
 turn on/off power supply for motor driver More...
 
int read_servo_state (int id, int *s)
 read servo status More...
 
int read_servo_alarm (int id, int *a)
 read servo alarms More...
 
int read_control_mode (int id, joint_control_mode *s)
 read joint control mode More...
 
int write_control_mode (int id, joint_control_mode s)
 write joint control mode More...
 
int read_actual_torques (double *torques)
 read array of current joint torques[Nm] More...
 
int read_command_torque (int id, double *torque)
 read command torque[Nm] More...
 
int write_command_torque (int id, double torque)
 write command torque[Nm] More...
 
int read_command_torques (double *torques)
 read array of command torques[Nm] More...
 
int write_command_torques (const double *torques)
 write array of command torques[Nm] More...
 
int read_command_angle (int id, double *angle)
 read command angle[rad] More...
 
int write_command_angle (int id, double angle)
 write command angle[rad] More...
 
int read_command_angles (double *angles)
 read array of command angles[rad] More...
 
int write_command_angles (const double *angles)
 write array of command angles[rad] More...
 
int read_pgain (int id, double *gain)
 read P gain[Nm/rad] More...
 
int write_pgain (int id, double gain)
 write P gain[Nm/rad] More...
 
int read_dgain (int id, double *gain)
 read D gain[Nm/(rad/s)] More...
 
int write_dgain (int id, double gain)
 write D gain[Nm/(rad/s)] More...
 
int read_actual_velocity (int id, double *vel)
 read actual angular velocity[rad/s] More...
 
int read_command_velocity (int id, double *vel)
 read command angular velocity[rad/s] More...
 
int write_command_velocity (int id, double vel)
 write command angular velocity[rad/s] More...
 
int read_actual_velocities (double *vels)
 read actual angular velocities[rad/s] More...
 
int read_command_velocities (double *vels)
 read command angular velocities[rad/s] More...
 
int write_command_velocities (const double *vels)
 write command angular velocities[rad/s] More...
 
int write_servo (int id, int com)
 turn on/off joint servo More...
 
int read_driver_temperature (int id, unsigned char *v)
 read temperature of motor driver[Celsius] More...
 
int read_calib_state (int id, int *s)
 read callibration state of joint More...
 
size_t length_of_extra_servo_state (int id)
 get length of extra servo states More...
 
int read_extra_servo_state (int id, int *state)
 read extra servo states More...
 
force sensor
int read_force_sensor (int id, double *forces)
 read output of force sensor More...
 
int read_force_offset (int id, double *offsets)
 read offset values for force sensor output More...
 
int write_force_offset (int id, double *offsets)
 write offset values for force sensor output More...
 
gyro sensor
int read_gyro_sensor (int id, double *rates)
 read output of gyro sensor More...
 
int read_gyro_sensor_offset (int id, double *offset)
 read offset values for gyro sensor output More...
 
int write_gyro_sensor_offset (int id, double *offset)
 write offset values for gyro sensor output More...
 
acceleromter
int read_accelerometer (int id, double *accels)
 read output of accelerometer More...
 
int read_accelerometer_offset (int id, double *offset)
 read offset values for accelerometer output More...
 
int write_accelerometer_offset (int id, double *offset)
 write offset values for accelerometer output More...
 
attitude sensor
int read_attitude_sensor (int id, double *att)
 read output of attitude sensor More...
 
int write_attitude_sensor_offset (int id, double *offset)
 
power supply
int read_power (double *v, double *a)
 read status of power source More...
 
thermometer
int read_temperature (int id, double *v)
 read thermometer More...
 
open/close
int open_iob (void)
 open connection with joint servo process More...
 
int close_iob (void)
 close connection with joint servo process More...
 
int reset_body (void)
 
int lock_iob ()
 lock access to iob More...
 
int unlock_iob ()
 unlock access to iob More...
 
int read_lock_owner (pid_t *pid)
 read id of the process whic is locking access to iob More...
 
unsigned long long read_iob_frame ()
 
int number_of_substeps ()
 
int wait_for_iob_signal ()
 wait until iob signal is issued More...
 
int set_signal_period (long period_ns)
 set the period of signals issued by wait_for_iob_signal() More...
 
long get_signal_period ()
 get the period of signals issued by wait_for_iob_signal() More...
 
int initializeJointAngle (const char *name, const char *option)
 initialize joint angle More...
 
int read_digital_input (char *dinput)
 read_digital_input, non-applicable bits are nop More...
 
int length_digital_input ()
 get_digital_input_length More...
 
int write_digital_output (const char *doutput)
 write_digital_output, non-applicable bits are nop More...
 
int write_digital_output_with_mask (const char *doutput, const char *dmask)
 write_digital_output, non-applicable bits are nop More...
 
int length_digital_output ()
 get_digital_output_length More...
 
int read_digital_output (char *doutput)
 read_digital_output, non-applicable bits are nop More...
 

Detailed Description

abstract interface for the robot hardware

Macro Definition Documentation

◆ E_ID

#define E_ID   -1

invalid joint(or sensor) id

◆ FALSE

#define FALSE   0

◆ JID_ALL

#define JID_ALL   -1

◆ JID_INVALID

#define JID_INVALID   -2

◆ MASK_OFF

#define MASK_OFF   1

◆ MASK_ON

#define MASK_ON   0

◆ OFF

#define OFF   0

◆ ON

#define ON   1

◆ SS_EMERGENCY

#define SS_EMERGENCY   0x8000

◆ SS_ENCODER_ERROR

#define SS_ENCODER_ERROR   0x400

◆ SS_FORWARD_LIMIT

#define SS_FORWARD_LIMIT   0x080

◆ SS_OTHER

#define SS_OTHER   0x800

◆ SS_OVER_CURRENT

#define SS_OVER_CURRENT   0x008

◆ SS_OVER_HEAT

#define SS_OVER_HEAT   0x010

◆ SS_OVER_LOAD

#define SS_OVER_LOAD   0x002

◆ SS_OVER_VELOCITY

#define SS_OVER_VELOCITY   0x004

◆ SS_OVER_VOLTAGE

#define SS_OVER_VOLTAGE   0x001

◆ SS_POSITION_ERROR

#define SS_POSITION_ERROR   0x200

◆ SS_RESERVED1

#define SS_RESERVED1   0x1000

◆ SS_RESERVED2

#define SS_RESERVED2   0x2000

◆ SS_RESERVED3

#define SS_RESERVED3   0x4000

◆ SS_REVERSE_LIMIT

#define SS_REVERSE_LIMIT   0x100

◆ SS_TORQUE_LIMIT

#define SS_TORQUE_LIMIT   0x020

◆ SS_VELOCITY_LIMIT

#define SS_VELOCITY_LIMIT   0x040

◆ TRUE

#define TRUE   1

Enumeration Type Documentation

◆ joint_control_mode

Enumerator
JCM_FREE 

free

JCM_POSITION 

position control

JCM_TORQUE 

torque control

JCM_VELOCITY 

velocity control

JCM_NUM 

Function Documentation

◆ close_iob()

int close_iob ( void  )

close connection with joint servo process

Return values
TRUEclosed successfully
FALSEotherwise

◆ get_signal_period()

long get_signal_period ( )

get the period of signals issued by wait_for_iob_signal()

Returns
the period of signals[ns]

◆ initializeJointAngle()

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

Referenced by python.hrpsys_config.HrpsysConfigurator::checkEncoders().

◆ length_digital_input()

int length_digital_input ( )

get_digital_input_length

Returns
length of digital input in bytes

◆ length_digital_output()

int length_digital_output ( )

get_digital_output_length

Returns
length of digital output in bytes

◆ length_of_extra_servo_state()

size_t length_of_extra_servo_state ( int  id)

get length of extra servo states

Parameters
idjoint id
Returns
length of extra servo states

◆ lock_iob()

int lock_iob ( )

lock access to iob

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

◆ number_of_accelerometers()

int number_of_accelerometers ( )

get the number of accelerometers

Returns
the number of accelerometers

◆ number_of_attitude_sensors()

int number_of_attitude_sensors ( )

get the number of attitude sensors

Returns
the number of attitude sensors

◆ number_of_force_sensors()

int number_of_force_sensors ( )

get the number of force sensors

Returns
the number of force sensors

◆ number_of_gyro_sensors()

int number_of_gyro_sensors ( )

get the number of gyro sensors

Returns
the number of gyro sensors

◆ number_of_joints()

int number_of_joints ( )

get the number of joints

Returns
the number of joints

◆ number_of_substeps()

int number_of_substeps ( )
Returns
the number of substeps

◆ open_iob()

int open_iob ( void  )

open connection with joint servo process

Return values
TRUEopened successfully
FALSEotherwise

◆ read_accelerometer()

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

◆ read_accelerometer_offset()

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

◆ read_actual_angle()

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

◆ read_actual_angles()

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

◆ read_actual_torques()

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

◆ read_actual_velocities()

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

◆ read_actual_velocity()

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

◆ read_angle_offset()

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

◆ read_attitude_sensor()

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

◆ read_calib_state()

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

◆ read_command_angle()

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

◆ read_command_angles()

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

◆ read_command_torque()

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

◆ read_command_torques()

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

◆ read_command_velocities()

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

◆ read_command_velocity()

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

◆ read_control_mode()

int read_control_mode ( int  id,
joint_control_mode s 
)

read joint control mode

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

◆ read_dgain()

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

◆ read_digital_input()

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

◆ read_digital_output()

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

◆ read_driver_temperature()

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

◆ read_extra_servo_state()

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

◆ read_force_offset()

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

◆ read_force_sensor()

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

◆ read_gyro_sensor()

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

◆ read_gyro_sensor_offset()

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

◆ read_iob_frame()

unsigned long long read_iob_frame ( )

◆ read_lock_owner()

int read_lock_owner ( pid_t *  pid)

read id of the process whic is locking access to iob

◆ read_pgain()

int read_pgain ( int  id,
double *  gain 
)

read P gain[Nm/rad]

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

◆ read_power()

int read_power ( double *  v,
double *  a 
)

read status of power source

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

◆ read_power_command()

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

◆ read_power_state()

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

◆ read_servo_alarm()

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

◆ read_servo_state()

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

◆ read_temperature()

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

◆ reset_body()

int reset_body ( void  )

◆ set_number_of_accelerometers()

int set_number_of_accelerometers ( int  num)

set the number of accelerometers

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

◆ set_number_of_force_sensors()

int set_number_of_force_sensors ( int  num)

set the number of force sensors

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

◆ set_number_of_gyro_sensors()

int set_number_of_gyro_sensors ( int  num)

set the number of gyro sensors

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

◆ set_number_of_joints()

int set_number_of_joints ( int  num)

set the number of joints

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

◆ set_signal_period()

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

◆ unlock_iob()

int unlock_iob ( )

unlock access to iob

◆ wait_for_iob_signal()

int wait_for_iob_signal ( )

wait until iob signal is issued

Returns
TRUE if signal is received successfully, FALSE otherwise

◆ write_accelerometer_offset()

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

◆ write_angle_offset()

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

◆ write_attitude_sensor_offset()

int write_attitude_sensor_offset ( int  id,
double *  offset 
)

◆ write_command_angle()

int write_command_angle ( int  id,
double  angle 
)

write command angle[rad]

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

◆ write_command_angles()

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

◆ write_command_torque()

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

◆ write_command_torques()

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

◆ write_command_velocities()

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

◆ write_command_velocity()

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

◆ write_control_mode()

int write_control_mode ( int  id,
joint_control_mode  s 
)

write joint control mode

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

◆ write_dgain()

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

◆ write_digital_output()

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

◆ write_digital_output_with_mask()

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

◆ write_force_offset()

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

◆ write_gyro_sensor_offset()

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

◆ write_pgain()

int write_pgain ( int  id,
double  gain 
)

write P gain[Nm/rad]

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

◆ write_power_command()

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

◆ write_servo()

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