2/22/2018
XH430-W350
http://support.robotis.com/en/product/actuator/dynamixel_x/xh_series/xh430-w350_main.htm
8/15
Hardware Error Status (70)
This value indicates hardware error status. For more details, please refer to the Shutdown(63).
Velocity I Gain (76), Velocity P Gain (78)
These values indicate Gains of Velocity Control Mode. Gains of Dynamixel’s internal controller can be calculated from Gains of the Control Table as shown below. The constant in each equations include
sampling time. Velocity P Gain of Dynamixel’s internal controller is abbreviated to KVP and that of the Control Table is abbreviated to KVP(TBL).
Controller Gain
Conversion Equations
Range
Description
Velocity I Gain(76)
KVI
KVI = KVI(TBL) / 65536
0 ~ 16383
I Gain
Velocity P Gain(78)
KVP
KVP = KVP(TBL) / 128
0 ~ 16383
P Gain
Below figure is a block diagram describing the velocity controller in Velocity Control Mode. When the instruction transmitted from the user is received by Dynamixel, it takes following steps until driving the
horn.
①
An Instruction from the user is transmitted via Dynamixel bus, then registered to Goal Velocity(104).
②
Goal Velocity(104) is converted to target velocity trajectory by Profile Acceleration(108).
③
The target velocity trajectory is stored at Velocity Trajectory(136).
④
PI controller calculates PWM output for the motor based on the target velocity trajectory.
⑤
Goal PWM(100) sets a limit on the calculated PWM output and decides the final PWM value.
⑥
The final PWM value is applied to the motor through an Inverter, and the horn of Dynamixel is driven.
⑦
Results are stored at Present Position(132), Present Velocity(128), Present PWM(124) and Present Current(126).
Note : Ka stands for Anti-windup Gain and ‘β’ is a conversion coefficient of position and velocity that cannot be modified by users. For more details about the PID controller, please refer to the below
website.
http://en.wikipedia.org/wiki/PID_controller
Position D Gain (80), Position I Gain (82), Position P Gain (84)
Feedforward 2nd Gain (88), Feedforward 1st Gain (90)
These Gains are used in Position Control Mode and Extended Position Control Mode. Gains of Dynamixel’s internal controller can be calculated from Gains of the Control Table as shown below. The
constant in each equations include sampling time. Position P Gain of Dynamixel’s internal controller is abbreviated to KPP and that of the Control Table is abbreviated to KPP(TBL).
Controller Gain
Conversion Equation
Range
Description
Position D Gain(76)
KPD
KPD = KPD(TBL) / 16
0 ~ 16383
D Gain
Position I Gain(76)
KPI
KPI = KPI(TBL) / 65536
0 ~ 16383
I Gain
Position P Gain(78)
KPP
KPP = KPP(TBL) / 128
0 ~ 16383
P Gain
Feedforward 2nd Gain(88)
KFF2nd
KFF2nd = KFF2nd(TBL) / 4
0 ~ 16383
Feedforward Acceleration Gain
Feedforward 1st Gain(90)
KFF1st
KFF1st = KFF1st(TBL) / 4
0 ~ 16383
Feedforward Velocity Gain
Below figure is a block diagram describing the position controller in Position Control Mode and Extended Position Control Mode. When the instruction from the user is received by Dynamixel, it takes
following steps until driving the horn.
①
An Instruction from the user is transmitted via Dynamixel bus, then registered to Goal Position(116).
②
Goal Position(116) is converted to target position trajectory and target velocity trajectory by Profile Velocity(112) and Profile Acceleration(108).
③
The target position trajectory and target velocity trajectory is stored at Position Trajectory(140) and Velocity Trajectory(136) respectively.
④
Feedforward and PID controller calculate PWM output for the motor based on target trajectories.
⑤
Goal PWM(100) sets a limit on the calculated PWM output and decides the final PWM value.
⑥
The final PWM value is applied to the motor through an Inverter, and the horn of Dynamixel is driven.
⑦
Results are stored at Present Position(132), Present Velocity(128), Present PWM(124) and Present Current(126).