dynamixel_item.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Taehun Lim (Darby), Ryan Shim */
18 
19 #include "../../include/dynamixel_workbench_toolbox/dynamixel_item.h"
20 
21 //=========================================================
22 // Servo register definitions
23 //=========================================================
24 
25 //_________________________________________________________
26 
27 static const char s_Acceleration_Limit[] = "Acceleration_Limit";
28 static const char s_Alarm_LED[] = "Alarm_LED";
29 static const char s_Baud_Rate[] = "Baud_Rate";
30 static const char s_Bus_Watchdog[] = "Bus_Watchdog";
31 static const char s_CCW_Angle_Limit[] = "CCW_Angle_Limit";
32 static const char s_CCW_Compliance_Margin[] = "CCW_Compliance_Margin";
33 static const char s_CCW_Compliance_Slope[] = "CCW_Compliance_Slope";
34 static const char s_Control_Mode[] = "Control_Mode";
35 static const char s_Current[] = "Current";
36 static const char s_Current_Limit[] = "Current_Limit";
37 static const char s_CW_Angle_Limit[] = "CW_Angle_Limit";
38 static const char s_CW_Compliance_Margin[] = "CW_Compliance_Margin";
39 static const char s_CW_Compliance_Slope[] = "CW_Compliance_Slope";
40 static const char s_D_gain[] = "D_gain";
41 static const char s_Drive_Mode[] = "Drive_Mode";
42 static const char s_External_Port_Mode_1[] = "External_Port_Mode_1";
43 static const char s_External_Port_Mode_2[] = "External_Port_Mode_2";
44 static const char s_External_Port_Mode_3[] = "External_Port_Mode_3";
45 static const char s_External_Port_Mode_4[] = "External_Port_Mode_4";
46 static const char s_External_Port_Data_1[] = "External_Port_Data_1";
47 static const char s_External_Port_Data_2[] = "External_Port_Data_2";
48 static const char s_External_Port_Data_3[] = "External_Port_Data_3";
49 static const char s_External_Port_Data_4[] = "External_Port_Data_4";
50 static const char s_Feedforward_1st_Gain[] = "Feedforward_1st_Gain";
51 static const char s_Feedforward_2nd_Gain[] = "Feedforward_2nd_Gain";
52 static const char s_Firmware_Version[] = "Firmware_Version";
53 static const char s_Goal_Acceleration[] = "Goal_Acceleration";
54 static const char s_Goal_Current[] = "Goal_Current";
55 static const char s_Goal_Position[] = "Goal_Position";
56 static const char s_Goal_PWM[] = "Goal_PWM";
57 static const char s_Goal_Torque[] = "Goal_Torque";
58 static const char s_Goal_Velocity[] = "Goal_Velocity";
59 static const char s_Hardware_Error_Status[] = "Hardware_Error_Status";
60 static const char s_Homing_Offset[] = "Homing_Offset";
61 static const char s_I_gain[] = "I_gain";
62 static const char s_ID[] = "ID";
63 static const char s_LED[] = "LED";
64 static const char s_LED_BLUE[] = "LED_BLUE";
65 static const char s_LED_GREEN[] = "LED_GREEN";
66 static const char s_LED_RED[] = "LED_RED";
67 static const char s_Lock[] = "Lock";
68 static const char s_Max_Position_Limit[] = "Max_Position_Limit";
69 static const char s_Max_Torque[] = "Max_Torque";
70 static const char s_Max_Voltage_Limit[] = "Max_Voltage_Limit";
71 static const char s_Min_Position_Limit[] = "Min_Position_Limit";
72 static const char s_Min_Voltage_Limit[] = "Min_Voltage_Limit";
73 static const char s_Model_Number[] = "Model_Number";
74 static const char s_Moving[] = "Moving";
75 static const char s_Moving_Speed[] = "Moving_Speed";
76 static const char s_Moving_Status[] = "Moving_Status";
77 static const char s_Moving_Threshold[] = "Moving_Threshold";
78 static const char s_Multi_Turn_Offset[] = "Multi_Turn_Offset";
79 static const char s_Operating_Mode[] = "Operating_Mode";
80 static const char s_P_gain[] = "P_gain";
81 static const char s_Position_D_Gain[] = "Position_D_Gain";
82 static const char s_Position_I_Gain[] = "Position_I_Gain";
83 static const char s_Position_P_Gain[] = "Position_P_Gain";
84 static const char s_Position_Trajectory[] = "Position_Trajectory";
85 static const char s_Present_Current[] = "Present_Current";
86 static const char s_Present_Input[] = "Present_Input";
87 static const char s_Present_Input_Voltage[] = "Present_Input_Voltage";
88 static const char s_Present_Load[] = "Present_Load";
89 static const char s_Present_Position[] = "Present_Position";
90 static const char s_Present_PWM[] = "Present_PWM";
91 static const char s_Present_Speed[] = "Present_Speed";
92 static const char s_Present_Temperature[] = "Present_Temperature";
93 static const char s_Present_Velocity[] = "Present_Velocity";
94 static const char s_Present_Voltage[] = "Present_Voltage";
95 static const char s_Profile_Acceleration[] = "Profile_Acceleration";
96 static const char s_Profile_Velocity[] = "Profile_Velocity";
97 static const char s_Protocol_Version[] = "Protocol_Version";
98 static const char s_Punch[] = "Punch";
99 static const char s_PWM_Limit[] = "PWM_Limit";
100 static const char s_PWM_Slope[] = "PWM_Slope";
101 static const char s_Realtime_Tick[] = "Realtime_Tick";
102 static const char s_Registered[] = "Registered";
103 static const char s_Registered_Instruction[] = "Registered_Instruction";
104 static const char s_Resolution_Divider[] = "Resolution_Divider";
105 static const char s_Return_Delay_Time[] = "Return_Delay_Time";
106 static const char s_Secondary_ID[] = "Secondary_ID";
107 static const char s_Sensored_Current[] = "Sensored_Current";
108 static const char s_Shutdown[] = "Shutdown";
109 static const char s_Status_Return_Level[] = "Status_Return_Level";
110 static const char s_Temperature_Limit[] = "Temperature_Limit";
111 static const char s_Torque_Control_Mode_Enable[] = "Torque_Control_Mode_Enable";
112 static const char s_Torque_Enable[] = "Torque_Enable";
113 static const char s_Torque_Limit[] = "Torque_Limit";
114 static const char s_Velocity_I_Gain[] = "Velocity_I_Gain";
115 static const char s_Velocity_Limit[] = "Velocity_Limit";
116 static const char s_Velocity_P_Gain[] = "Velocity_P_Gain";
117 static const char s_Velocity_Trajectory[] = "Velocity_Trajectory";
118 
119 //_________________________________________________________
120 
121 //---------------------------------------------------------
122 // AX servos - (num == AX_12A || num == AX_12W || num == AX_18A)
123 //---------------------------------------------------------
124 static const ControlItem items_AX[]{
125  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
126  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
127  {s_ID, 3, sizeof(s_ID) - 1, 1},
128  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
129  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
130  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
131  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
132  {s_Temperature_Limit, 11, sizeof(s_Temperature_Limit) - 1, 1},
133  {s_Min_Voltage_Limit, 12, sizeof(s_Min_Voltage_Limit) - 1, 1},
134  {s_Max_Voltage_Limit, 13, sizeof(s_Max_Voltage_Limit) - 1, 1},
135  {s_Max_Torque, 14, sizeof(s_Max_Torque) - 1, 2},
136  {s_Status_Return_Level, 16, sizeof(s_Status_Return_Level) - 1, 1},
137  {s_Alarm_LED, 17, sizeof(s_Alarm_LED) - 1, 1},
138  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
139 
140  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
141  {s_LED, 25, sizeof(s_LED) - 1, 1},
142  {s_CW_Compliance_Margin, 26, sizeof(s_CW_Compliance_Margin) - 1, 1},
143  {s_CCW_Compliance_Margin, 27, sizeof(s_CCW_Compliance_Margin) - 1, 1},
144  {s_CW_Compliance_Slope, 28, sizeof(s_CW_Compliance_Slope) - 1, 1},
145  {s_CCW_Compliance_Slope, 29, sizeof(s_CCW_Compliance_Slope) - 1, 1},
146  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
147  {s_Moving_Speed, 32, sizeof(s_Moving_Speed) - 1, 2},
148  {s_Torque_Limit, 34, sizeof(s_Torque_Limit) - 1, 2},
149  {s_Present_Position, 36, sizeof(s_Present_Position) - 1, 2},
150  {s_Present_Speed, 38, sizeof(s_Present_Speed) - 1, 2},
151  {s_Present_Load, 40, sizeof(s_Present_Load) - 1, 2},
152  {s_Present_Voltage, 42, sizeof(s_Present_Voltage) - 1, 1},
153  {s_Present_Temperature, 43, sizeof(s_Present_Temperature) - 1, 1},
154  {s_Registered, 44, sizeof(s_Registered) - 1, 1},
155  {s_Moving, 46, sizeof(s_Moving) - 1, 1},
156  {s_Lock, 47, sizeof(s_Lock) - 1, 1},
157  {s_Punch, 48, sizeof(s_Punch) - 1, 2}};
158 #define COUNT_AX_ITEMS (sizeof(items_AX) / sizeof(items_AX[0]))
159 
160 static const ModelInfo info_AX = {0.11,
161  0,
162  512,
163  1024,
164  -2.61799,
165  2.61799};
166 
167 //---------------------------------------------------------
168 // RX servos - (num == RX_10 || num == RX_24F || num == RX_28 || num == RX_64)
169 //---------------------------------------------------------
170 static const ControlItem items_RX[]{
171  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
172  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
173  {s_ID, 3, sizeof(s_ID) - 1, 1},
174  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
175  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
176  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
177  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
178  {s_Temperature_Limit, 11, sizeof(s_Temperature_Limit) - 1, 1},
179  {s_Min_Voltage_Limit, 12, sizeof(s_Min_Voltage_Limit) - 1, 1},
180  {s_Max_Voltage_Limit, 13, sizeof(s_Max_Voltage_Limit) - 1, 1},
181  {s_Max_Torque, 14, sizeof(s_Max_Torque) - 1, 2},
182  {s_Status_Return_Level, 16, sizeof(s_Status_Return_Level) - 1, 1},
183  {s_Alarm_LED, 17, sizeof(s_Alarm_LED) - 1, 1},
184  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
185 
186  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
187  {s_LED, 25, sizeof(s_LED) - 1, 1},
188  {s_CW_Compliance_Margin, 26, sizeof(s_CW_Compliance_Margin) - 1, 1},
189  {s_CCW_Compliance_Margin, 27, sizeof(s_CCW_Compliance_Margin) - 1, 1},
190  {s_CW_Compliance_Slope, 28, sizeof(s_CW_Compliance_Slope) - 1, 1},
191  {s_CCW_Compliance_Slope, 29, sizeof(s_CCW_Compliance_Slope) - 1, 1},
192  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
193  {s_Moving_Speed, 32, sizeof(s_Moving_Speed) - 1, 2},
194  {s_Torque_Limit, 34, sizeof(s_Torque_Limit) - 1, 2},
195  {s_Present_Position, 36, sizeof(s_Present_Position) - 1, 2},
196  {s_Present_Speed, 38, sizeof(s_Present_Speed) - 1, 2},
197  {s_Present_Load, 40, sizeof(s_Present_Load) - 1, 2},
198  {s_Present_Voltage, 42, sizeof(s_Present_Voltage) - 1, 1},
199  {s_Present_Temperature, 43, sizeof(s_Present_Temperature) - 1, 1},
200  {s_Registered, 44, sizeof(s_Registered) - 1, 1},
201  {s_Moving, 46, sizeof(s_Moving) - 1, 1},
202  {s_Lock, 47, sizeof(s_Lock) - 1, 1},
203  {s_Punch, 48, sizeof(s_Punch) - 1, 2}};
204 
205 #define COUNT_RX_ITEMS (sizeof(items_RX) / sizeof(items_RX[0]))
206 
207 static const ModelInfo info_RX = {0.11,
208  0,
209  512,
210  1024,
211  -2.61799,
212  2.61799};
213 
214 //---------------------------------------------------------
215 // EX servos - (num == EX_106)
216 //---------------------------------------------------------
217 static const ControlItem items_EX[]{
218  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
219  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
220  {s_ID, 3, sizeof(s_ID) - 1, 1},
221  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
222  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
223  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
224  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
225  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
226  {s_Temperature_Limit, 11, sizeof(s_Temperature_Limit) - 1, 1},
227  {s_Min_Voltage_Limit, 12, sizeof(s_Min_Voltage_Limit) - 1, 1},
228  {s_Max_Voltage_Limit, 13, sizeof(s_Max_Voltage_Limit) - 1, 1},
229  {s_Max_Torque, 14, sizeof(s_Max_Torque) - 1, 2},
230  {s_Status_Return_Level, 16, sizeof(s_Status_Return_Level) - 1, 1},
231  {s_Alarm_LED, 17, sizeof(s_Alarm_LED) - 1, 1},
232  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
233 
234  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
235  {s_LED, 25, sizeof(s_LED) - 1, 1},
236  {s_CW_Compliance_Margin, 26, sizeof(s_CW_Compliance_Margin) - 1, 1},
237  {s_CCW_Compliance_Margin, 27, sizeof(s_CCW_Compliance_Margin) - 1, 1},
238  {s_CW_Compliance_Slope, 28, sizeof(s_CW_Compliance_Slope) - 1, 1},
239  {s_CCW_Compliance_Slope, 29, sizeof(s_CCW_Compliance_Slope) - 1, 1},
240  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
241  {s_Moving_Speed, 34, sizeof(s_Moving_Speed) - 1, 2},
242  {s_Torque_Limit, 35, sizeof(s_Torque_Limit) - 1, 2},
243  {s_Present_Position, 36, sizeof(s_Present_Position) - 1, 2},
244  {s_Present_Speed, 38, sizeof(s_Present_Speed) - 1, 2},
245  {s_Present_Load, 40, sizeof(s_Present_Load) - 1, 2},
246  {s_Present_Voltage, 42, sizeof(s_Present_Voltage) - 1, 1},
247  {s_Present_Temperature, 43, sizeof(s_Present_Temperature) - 1, 1},
248  {s_Registered, 44, sizeof(s_Registered) - 1, 1},
249  {s_Moving, 46, sizeof(s_Moving) - 1, 1},
250  {s_Lock, 47, sizeof(s_Lock) - 1, 1},
251  {s_Punch, 48, sizeof(s_Punch) - 1, 2},
252  {s_Sensored_Current, 56, sizeof(s_Sensored_Current) - 1, 2}};
253 
254 #define COUNT_EX_ITEMS (sizeof(items_EX) / sizeof(items_EX[0]))
255 
256 static const ModelInfo info_EX = {0.11,
257  0,
258  2048,
259  4096,
260  -2.18969008,
261  2.18969008};
262 
263 //---------------------------------------------------------
264 // MX Protocol 1 servos - (num == MX_12W || num == MX_28)
265 //---------------------------------------------------------
266 static const ControlItem items_MX[]{
267  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
268  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
269  {s_ID, 3, sizeof(s_ID) - 1, 1},
270  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
271  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
272  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
273  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
274  {s_Temperature_Limit, 11, sizeof(s_Temperature_Limit) - 1, 1},
275  {s_Min_Voltage_Limit, 12, sizeof(s_Min_Voltage_Limit) - 1, 1},
276  {s_Max_Voltage_Limit, 13, sizeof(s_Max_Voltage_Limit) - 1, 1},
277  {s_Max_Torque, 14, sizeof(s_Max_Torque) - 1, 2},
278  {s_Status_Return_Level, 16, sizeof(s_Status_Return_Level) - 1, 1},
279  {s_Alarm_LED, 17, sizeof(s_Alarm_LED) - 1, 1},
280  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
281  {s_Multi_Turn_Offset, 20, sizeof(s_Multi_Turn_Offset) - 1, 2},
282  {s_Resolution_Divider, 22, sizeof(s_Resolution_Divider) - 1, 1},
283 
284  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
285  {s_LED, 25, sizeof(s_LED) - 1, 1},
286  {s_D_gain, 26, sizeof(s_D_gain) - 1, 1},
287  {s_I_gain, 27, sizeof(s_I_gain) - 1, 1},
288  {s_P_gain, 28, sizeof(s_P_gain) - 1, 1},
289  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
290  {s_Moving_Speed, 32, sizeof(s_Moving_Speed) - 1, 2},
291  {s_Torque_Limit, 34, sizeof(s_Torque_Limit) - 1, 2},
292  {s_Present_Position, 36, sizeof(s_Present_Position) - 1, 2},
293  {s_Present_Speed, 38, sizeof(s_Present_Speed) - 1, 2},
294  {s_Present_Load, 40, sizeof(s_Present_Load) - 1, 2},
295  {s_Present_Voltage, 42, sizeof(s_Present_Voltage) - 1, 1},
296  {s_Present_Temperature, 43, sizeof(s_Present_Temperature) - 1, 1},
297  {s_Registered, 44, sizeof(s_Registered) - 1, 1},
298  {s_Moving, 46, sizeof(s_Moving) - 1, 1},
299  {s_Lock, 47, sizeof(s_Lock) - 1, 1},
300  {s_Punch, 48, sizeof(s_Punch) - 1, 2},
301  {s_Goal_Acceleration, 73, sizeof(s_Goal_Acceleration) - 1, 1}};
302 
303 #define COUNT_MX_ITEMS (sizeof(items_MX) / sizeof(items_MX[0]))
304 
305 static const ModelInfo info_MX = {0.11,
306  0,
307  2048,
308  4096,
309  -3.14159265,
310  3.14159265};
311 
312 //---------------------------------------------------------
313 // MX Protocol 2 servos - (num == MX_28_2)
314 //---------------------------------------------------------
315 static const ControlItem items_MX2[]{
316  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
317  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
318  {s_ID, 7, sizeof(s_ID) - 1, 1},
319  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
320  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
321  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
322  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
323  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
324  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
325  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
326  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
327  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
328  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
329  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
330  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
331  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
332  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
333  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
334  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
335  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
336 
337  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
338  {s_LED, 65, sizeof(s_LED) - 1, 1},
339  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
341  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
342  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
343  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
344  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
345  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
346  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
347  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
348  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
349  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
350  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
351  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
352  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
353  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
354  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
355  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
356  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
357  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
358  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
359  {s_Present_Load, 126, sizeof(s_Present_Load) - 1, 2},
360  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
361  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
362  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
363  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
364  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
365  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
366 
367 #define COUNT_MX2_ITEMS (sizeof(items_MX2) / sizeof(items_MX2[0]))
368 
369 static const ModelInfo info_MX2 = {0.229,
370  0,
371  2048,
372  4096,
373  -3.14159265,
374  3.14159265};
375 
376 //---------------------------------------------------------
377 // EXT MX Protocol 1 servos - (num == MX_64 || num == MX_106)
378 //---------------------------------------------------------
379 static const ControlItem items_EXTMX[]{
380  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
381  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
382  {s_ID, 3, sizeof(s_ID) - 1, 1},
383  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
384  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
385  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
386  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
387  {s_Temperature_Limit, 11, sizeof(s_Temperature_Limit) - 1, 1},
388  {s_Min_Voltage_Limit, 12, sizeof(s_Min_Voltage_Limit) - 1, 1},
389  {s_Max_Voltage_Limit, 13, sizeof(s_Max_Voltage_Limit) - 1, 1},
390  {s_Max_Torque, 14, sizeof(s_Max_Torque) - 1, 2},
391  {s_Status_Return_Level, 16, sizeof(s_Status_Return_Level) - 1, 1},
392  {s_Alarm_LED, 17, sizeof(s_Alarm_LED) - 1, 1},
393  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
394  {s_Multi_Turn_Offset, 20, sizeof(s_Multi_Turn_Offset) - 1, 2},
395  {s_Resolution_Divider, 22, sizeof(s_Resolution_Divider) - 1, 1},
396 
397  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
398  {s_LED, 25, sizeof(s_LED) - 1, 1},
399  {s_D_gain, 26, sizeof(s_D_gain) - 1, 1},
400  {s_I_gain, 27, sizeof(s_I_gain) - 1, 1},
401  {s_P_gain, 28, sizeof(s_P_gain) - 1, 1},
402  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
403  {s_Moving_Speed, 32, sizeof(s_Moving_Speed) - 1, 2},
404  {s_Torque_Limit, 34, sizeof(s_Torque_Limit) - 1, 2},
405  {s_Present_Position, 36, sizeof(s_Present_Position) - 1, 2},
406  {s_Present_Speed, 38, sizeof(s_Present_Speed) - 1, 2},
407  {s_Present_Load, 40, sizeof(s_Present_Load) - 1, 2},
408  {s_Present_Voltage, 42, sizeof(s_Present_Voltage) - 1, 1},
409  {s_Present_Temperature, 43, sizeof(s_Present_Temperature) - 1, 1},
410  {s_Registered, 44, sizeof(s_Registered) - 1, 1},
411  {s_Moving, 46, sizeof(s_Moving) - 1, 1},
412  {s_Lock, 47, sizeof(s_Lock) - 1, 1},
413  {s_Punch, 48, sizeof(s_Punch) - 1, 2},
414  {s_Current, 68, sizeof(s_Current) - 1, 2},
416  {s_Goal_Torque, 71, sizeof(s_Goal_Torque) - 1, 2},
417  {s_Goal_Acceleration, 73, sizeof(s_Goal_Acceleration) - 1, 1}};
418 
419 #define COUNT_EXTMX_ITEMS (sizeof(items_EXTMX) / sizeof(items_EXTMX[0]))
420 
421 static const ModelInfo info_EXTMX = {0.11,
422  0,
423  2048,
424  4096,
425  -3.14159265,
426  3.14159265};
427 
428 //---------------------------------------------------------
429 // EXT MX Protocol 2 Servos - (num == MX_64_2 || num == MX_106_2)
430 //---------------------------------------------------------
431 static const ControlItem items_EXTMX2[]{
432  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
433  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
434  {s_ID, 7, sizeof(s_ID) - 1, 1},
435  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
436  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
437  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
438  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
439  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
440  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
441  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
442  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
443  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
444  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
445  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
446  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
447  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
448  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
449  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
450  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
451  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
452  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
453 
454  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
455  {s_LED, 65, sizeof(s_LED) - 1, 1},
456  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
458  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
459  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
460  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
461  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
462  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
463  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
464  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
465  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
466  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
467  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
468  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
469  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
470  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
471  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
472  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
473  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
474  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
475  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
476  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
477  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
478  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
479  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
480  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
481  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
482  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
483  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
484 
485 #define COUNT_EXTMX2_ITEMS (sizeof(items_EXTMX2) / sizeof(items_EXTMX2[0]))
486 
487 static const ModelInfo info_EXTMX2 = {0.229,
488  0,
489  2048,
490  4096,
491  -3.14159265,
492  3.14159265};
493 
494 //---------------------------------------------------------
495 // XL320 - (num == XL_320)
496 //---------------------------------------------------------
497 static const ControlItem items_XL320[]{
498  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
499  {s_Firmware_Version, 2, sizeof(s_Firmware_Version) - 1, 1},
500  {s_ID, 3, sizeof(s_ID) - 1, 1},
501  {s_Baud_Rate, 4, sizeof(s_Baud_Rate) - 1, 1},
502  {s_Return_Delay_Time, 5, sizeof(s_Return_Delay_Time) - 1, 1},
503  {s_CW_Angle_Limit, 6, sizeof(s_CW_Angle_Limit) - 1, 2},
504  {s_CCW_Angle_Limit, 8, sizeof(s_CCW_Angle_Limit) - 1, 2},
505  {s_Control_Mode, 11, sizeof(s_Control_Mode) - 1, 1},
506  {s_Temperature_Limit, 12, sizeof(s_Temperature_Limit) - 1, 1},
507  {s_Min_Voltage_Limit, 13, sizeof(s_Min_Voltage_Limit) - 1, 1},
508  {s_Max_Voltage_Limit, 14, sizeof(s_Max_Voltage_Limit) - 1, 1},
509  {s_Max_Torque, 15, sizeof(s_Max_Torque) - 1, 2},
510  {s_Status_Return_Level, 17, sizeof(s_Status_Return_Level) - 1, 1},
511  {s_Shutdown, 18, sizeof(s_Shutdown) - 1, 1},
512 
513  {s_Torque_Enable, 24, sizeof(s_Torque_Enable) - 1, 1},
514  {s_LED, 25, sizeof(s_LED) - 1, 1},
515  {s_D_gain, 27, sizeof(s_D_gain) - 1, 1},
516  {s_I_gain, 28, sizeof(s_I_gain) - 1, 1},
517  {s_P_gain, 29, sizeof(s_P_gain) - 1, 1},
518  {s_Goal_Position, 30, sizeof(s_Goal_Position) - 1, 2},
519  {s_Moving_Speed, 32, sizeof(s_Moving_Speed) - 1, 2},
520  {s_Torque_Limit, 34, sizeof(s_Torque_Limit) - 1, 2},
521  {s_Present_Position, 37, sizeof(s_Present_Position) - 1, 2},
522  {s_Present_Speed, 39, sizeof(s_Present_Speed) - 1, 2},
523  {s_Present_Load, 41, sizeof(s_Present_Load) - 1, 2},
524  {s_Present_Voltage, 45, sizeof(s_Present_Voltage) - 1, 1},
525  {s_Present_Temperature, 46, sizeof(s_Present_Temperature) - 1, 1},
526  {s_Registered, 47, sizeof(s_Registered) - 1, 1},
527  {s_Moving, 49, sizeof(s_Moving) - 1, 1},
528  {s_Hardware_Error_Status, 50, sizeof(s_Hardware_Error_Status) - 1, 1},
529  {s_Punch, 51, sizeof(s_Punch) - 1, 2}};
530 
531 #define COUNT_XL320_ITEMS (sizeof(items_XL320) / sizeof(items_XL320[0]))
532 
533 static const ModelInfo info_XL320 = {0.11,
534  0,
535  512,
536  1024,
537  -2.61799,
538  2.61799};
539 
540 //---------------------------------------------------------
541 // XL330 - (num == XL330_M077, XL330_M288)
542 //---------------------------------------------------------
543 static const ControlItem items_XL330[]{
544  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
545  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
546  {s_ID, 7, sizeof(s_ID) - 1, 1},
547  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
548  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
549  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
550  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
551  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
552  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
553  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
554  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
555  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
556  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
557  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
558  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
559  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
560  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
561  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
562  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
563  {s_PWM_Slope, 62, sizeof(s_PWM_Slope) - 1, 1},
564  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
565  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
566  {s_LED, 65, sizeof(s_LED) - 1, 1},
567  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
569  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
570  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
571  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
572  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
573  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
574  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
575  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
576  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
577  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
578  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
579  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
580  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
581  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
582  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
583  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
584  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
585  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
586  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
587  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
588  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
589  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
590  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
591  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
592  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
593  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
594  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
595 
596 #define COUNT_XL330_ITEMS (sizeof(items_XL330) / sizeof(items_XL330[0]))
597 
598 static const ModelInfo info_XL330 = {0.229,
599  0,
600  2048,
601  4096,
602  -3.14159265,
603  3.14159265};
604 
605 //---------------------------------------------------------
606 // XL - (num == XL430_W250, XL430_W250_2, XC430_W150, XC430_W240, XC430_W250_2)
607 //---------------------------------------------------------
608 static const ControlItem items_XL[]{
609  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
610  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
611  {s_ID, 7, sizeof(s_ID) - 1, 1},
612  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
613  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
614  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
615  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
616  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
617  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
618  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
619  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
620  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
621  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
622  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
623  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
624  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
625  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
626  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
627  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
628  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
629 
630  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
631  {s_LED, 65, sizeof(s_LED) - 1, 1},
632  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
634  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
635  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
636  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
637  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
638  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
639  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
640  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
641  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
642  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
643  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
644  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
645  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
646  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
647  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
648  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
649  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
650  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
651  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
652  {s_Present_Load, 126, sizeof(s_Present_Load) - 1, 2},
653  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
654  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
655  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
656  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
657  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
658  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
659 
660 #define COUNT_XL_ITEMS (sizeof(items_XL) / sizeof(items_XL[0]))
661 
662 static const ModelInfo info_XL = {0.229,
663  0,
664  2048,
665  4096,
666  -3.14159265,
667  3.14159265};
668 
669 //---------------------------------------------------------
670 // XM - (num == XM430_W210 || num == XM430_W350)
671 //---------------------------------------------------------
672 static const ControlItem items_XM[]{
673  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
674  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
675  {s_ID, 7, sizeof(s_ID) - 1, 1},
676  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
677  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
678  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
679  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
680  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
681  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
682  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
683  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
684  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
685  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
686  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
687  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
688  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
689  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
690  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
691  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
692  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
693  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
694 
695  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
696  {s_LED, 65, sizeof(s_LED) - 1, 1},
697  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
699  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
700  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
701  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
702  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
703  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
704  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
705  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
706  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
707  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
708  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
709  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
710  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
711  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
712  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
713  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
714  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
715  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
716  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
717  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
718  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
719  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
720  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
721  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
722  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
723  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
724  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
725 
726 #define COUNT_XM_ITEMS (sizeof(items_XM) / sizeof(items_XM[0]))
727 
728 static const ModelInfo info_XM = {0.229,
729  0,
730  2048,
731  4096,
732  -3.14159265,
733  3.14159265};
734 
735 //---------------------------------------------------------
736 // EXTXM - (num == XM540_W150 || num == XM540_W270)
737 //---------------------------------------------------------
738 static const ControlItem items_EXTXM[]{
739  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
740  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
741  {s_ID, 7, sizeof(s_ID) - 1, 1},
742  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
743  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
744  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
745  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
746  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
747  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
748  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
749  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
750  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
751  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
752  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
753  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
754  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
755  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
756  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
757  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
758  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
759  {s_External_Port_Mode_1, 56, sizeof(s_External_Port_Mode_1) - 1, 1},
760  {s_External_Port_Mode_2, 57, sizeof(s_External_Port_Mode_2) - 1, 1},
761  {s_External_Port_Mode_3, 58, sizeof(s_External_Port_Mode_3) - 1, 1},
762  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
763 
764  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
765  {s_LED, 65, sizeof(s_LED) - 1, 1},
766  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
768  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
769  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
770  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
771  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
772  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
773  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
774  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
775  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
776  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
777  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
778  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
779  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
780  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
781  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
782  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
783  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
784  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
785  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
786  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
787  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
788  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
789  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
790  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
791  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
792  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
793  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1},
794  {s_External_Port_Data_1, 152, sizeof(s_External_Port_Data_1) - 1, 2},
795  {s_External_Port_Data_2, 154, sizeof(s_External_Port_Data_2) - 1, 2},
796  {s_External_Port_Data_3, 156, sizeof(s_External_Port_Data_3) - 1, 2}};
797 
798 #define COUNT_EXTXM_ITEMS (sizeof(items_EXTXM) / sizeof(items_EXTXM[0]))
799 
800 static const ModelInfo info_EXTXM = {0.229,
801  0,
802  2048,
803  4096,
804  -3.14159265,
805  3.14159265};
806 
807 //---------------------------------------------------------
808 // XH - (num == XH430_V210 || num == XH430_V350 || num == XH430_W210 || num == XH430_W350)
809 //---------------------------------------------------------
810 static const ControlItem items_XH[]{
811  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
812  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
813  {s_ID, 7, sizeof(s_ID) - 1, 1},
814  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
815  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
816  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
817  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
818  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
819  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
820  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
821  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
822  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
823  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
824  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
825  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
826  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
827  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
828  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
829  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
830  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
831  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
832 
833  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
834  {s_LED, 65, sizeof(s_LED) - 1, 1},
835  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
837  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
838  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
839  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
840  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
841  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
842  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
843  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
844  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
845  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
846  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
847  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
848  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
849  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
850  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
851  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
852  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
853  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
854  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
855  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
856  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
857  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
858  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
859  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
860  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
861  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
862  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
863 
864 #define COUNT_XH_ITEMS (sizeof(items_XH) / sizeof(items_XH[0]))
865 
866 static const ModelInfo info_XH = {0.229,
867  0,
868  2048,
869  4096,
870  -3.14159265,
871  3.14159265};
872 
873 //---------------------------------------------------------
874 // EXTXH - (num == XH540_W150 || num == XH540_W270 || num == XH540_V150 || num == XH540_W270)
875 //---------------------------------------------------------
876 static const ControlItem items_EXTXH[]{
877  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
878  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
879  {s_ID, 7, sizeof(s_ID) - 1, 1},
880  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
881  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
882  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
883  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
884  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
885  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
886  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
887  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
888  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
889  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
890  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
891  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
892  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
893  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
894  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
895  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
896  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
897  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
898 
899  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
900  {s_LED, 65, sizeof(s_LED) - 1, 1},
901  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
903  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
904  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
905  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
906  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
907  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
908  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
909  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
910  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
911  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
912  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
913  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
914  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
915  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
916  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
917  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
918  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
919  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
920  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
921  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
922  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
923  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
924  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
925  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
926  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
927  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
928  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
929 
930 #define COUNT_EXTXH_ITEMS (sizeof(items_EXTXH) / sizeof(items_EXTXH[0]))
931 
932 static const ModelInfo info_EXTXH = {0.229,
933  0,
934  2048,
935  4096,
936  -3.14159265,
937  3.14159265};
938 
939 //---------------------------------------------------------
940 // XW - (num == XW540_T260 || XW540_T140)
941 //---------------------------------------------------------
942 static const ControlItem items_XW[]{
943  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
944  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
945  {s_ID, 7, sizeof(s_ID) - 1, 1},
946  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
947  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
948  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
949  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
950  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
951  {s_Protocol_Version, 13, sizeof(s_Protocol_Version) - 1, 1},
952  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
953  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
954  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
955  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
956  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
957  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
958  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
959  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
960  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
961  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
962  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
963  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
964 
965  {s_Torque_Enable, 64, sizeof(s_Torque_Enable) - 1, 1},
966  {s_Status_Return_Level, 68, sizeof(s_Status_Return_Level) - 1, 1},
968  {s_Hardware_Error_Status, 70, sizeof(s_Hardware_Error_Status) - 1, 1},
969  {s_Velocity_I_Gain, 76, sizeof(s_Velocity_I_Gain) - 1, 2},
970  {s_Velocity_P_Gain, 78, sizeof(s_Velocity_P_Gain) - 1, 2},
971  {s_Position_D_Gain, 80, sizeof(s_Position_D_Gain) - 1, 2},
972  {s_Position_I_Gain, 82, sizeof(s_Position_I_Gain) - 1, 2},
973  {s_Position_P_Gain, 84, sizeof(s_Position_P_Gain) - 1, 2},
974  {s_Feedforward_2nd_Gain, 88, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
975  {s_Feedforward_1st_Gain, 90, sizeof(s_Feedforward_1st_Gain) - 1, 2},
976  {s_Bus_Watchdog, 98, sizeof(s_Bus_Watchdog) - 1, 1},
977  {s_Goal_PWM, 100, sizeof(s_Goal_PWM) - 1, 2},
978  {s_Goal_Current, 102, sizeof(s_Goal_Current) - 1, 2},
979  {s_Goal_Velocity, 104, sizeof(s_Goal_Velocity) - 1, 4},
980  {s_Profile_Acceleration, 108, sizeof(s_Profile_Acceleration) - 1, 4},
981  {s_Profile_Velocity, 112, sizeof(s_Profile_Velocity) - 1, 4},
982  {s_Goal_Position, 116, sizeof(s_Goal_Position) - 1, 4},
983  {s_Realtime_Tick, 120, sizeof(s_Realtime_Tick) - 1, 2},
984  {s_Moving, 122, sizeof(s_Moving) - 1, 1},
985  {s_Moving_Status, 123, sizeof(s_Moving_Status) - 1, 1},
986  {s_Present_PWM, 124, sizeof(s_Present_PWM) - 1, 2},
987  {s_Present_Current, 126, sizeof(s_Present_Current) - 1, 2},
988  {s_Present_Velocity, 128, sizeof(s_Present_Velocity) - 1, 4},
989  {s_Present_Position, 132, sizeof(s_Present_Position) - 1, 4},
990  {s_Velocity_Trajectory, 136, sizeof(s_Velocity_Trajectory) - 1, 4},
991  {s_Position_Trajectory, 140, sizeof(s_Position_Trajectory) - 1, 4},
992  {s_Present_Input_Voltage, 144, sizeof(s_Present_Input_Voltage) - 1, 2},
993  {s_Present_Temperature, 146, sizeof(s_Present_Temperature) - 1, 1}};
994 
995 #define COUNT_XW_ITEMS (sizeof(items_XW) / sizeof(items_XW[0]))
996 
997 static const ModelInfo info_XW = {0.229,
998  0,
999  2048,
1000  4096,
1001  -3.14159265,
1002  3.14159265};
1003 
1004 //---------------------------------------------------------
1005 // PRO - (num == PRO_L42_10_S300_R)
1006 //---------------------------------------------------------
1007 static const ControlItem items_PRO[]{
1008  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1009  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1010  {s_ID, 7, sizeof(s_ID) - 1, 1},
1011  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1012  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1013  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1014  {s_Moving_Threshold, 17, sizeof(s_Moving_Threshold) - 1, 4},
1015  {s_Temperature_Limit, 21, sizeof(s_Temperature_Limit) - 1, 1},
1016  {s_Max_Voltage_Limit, 22, sizeof(s_Max_Voltage_Limit) - 1, 2},
1017  {s_Min_Voltage_Limit, 24, sizeof(s_Min_Voltage_Limit) - 1, 2},
1018  {s_Acceleration_Limit, 26, sizeof(s_Acceleration_Limit) - 1, 4},
1019  {s_Torque_Limit, 30, sizeof(s_Torque_Limit) - 1, 2},
1020  {s_Velocity_Limit, 32, sizeof(s_Velocity_Limit) - 1, 4},
1021  {s_Max_Position_Limit, 36, sizeof(s_Max_Position_Limit) - 1, 4},
1022  {s_Min_Position_Limit, 40, sizeof(s_Min_Position_Limit) - 1, 4},
1023  {s_External_Port_Mode_1, 44, sizeof(s_External_Port_Mode_1) - 1, 1},
1024  {s_External_Port_Mode_2, 45, sizeof(s_External_Port_Mode_2) - 1, 1},
1025  {s_External_Port_Mode_3, 46, sizeof(s_External_Port_Mode_3) - 1, 1},
1026  {s_External_Port_Mode_4, 47, sizeof(s_External_Port_Mode_4) - 1, 1},
1027  {s_Shutdown, 48, sizeof(s_Shutdown) - 1, 1},
1028 
1029  {s_Torque_Enable, 562, sizeof(s_Torque_Enable) - 1, 1},
1030  {s_LED_RED, 563, sizeof(s_LED_RED) - 1, 1},
1031  {s_LED_GREEN, 564, sizeof(s_LED_GREEN) - 1, 1},
1032  {s_LED_BLUE, 565, sizeof(s_LED_BLUE) - 1, 1},
1033  {s_Velocity_I_Gain, 586, sizeof(s_Velocity_I_Gain) - 1, 2},
1034  {s_Velocity_P_Gain, 588, sizeof(s_Velocity_P_Gain) - 1, 2},
1035  {s_Position_P_Gain, 594, sizeof(s_Position_P_Gain) - 1, 2},
1036  {s_Goal_Position, 596, sizeof(s_Goal_Position) - 1, 4},
1037  {s_Goal_Velocity, 600, sizeof(s_Goal_Velocity) - 1, 4},
1038  {s_Goal_Torque, 604, sizeof(s_Goal_Torque) - 1, 2},
1039  {s_Goal_Acceleration, 606, sizeof(s_Goal_Acceleration) - 1, 4},
1040  {s_Moving, 610, sizeof(s_Moving) - 1, 1},
1041  {s_Present_Position, 611, sizeof(s_Present_Position) - 1, 4},
1042  {s_Present_Velocity, 615, sizeof(s_Present_Velocity) - 1, 4},
1043  {s_Present_Current, 621, sizeof(s_Present_Current) - 1, 2},
1044  {s_Present_Input_Voltage, 623, sizeof(s_Present_Input_Voltage) - 1, 2},
1045  {s_Present_Temperature, 625, sizeof(s_Present_Temperature) - 1, 1},
1046  {s_External_Port_Data_1, 626, sizeof(s_External_Port_Data_1) - 1, 2},
1047  {s_External_Port_Data_2, 628, sizeof(s_External_Port_Data_2) - 1, 2},
1048  {s_External_Port_Data_3, 630, sizeof(s_External_Port_Data_3) - 1, 2},
1049  {s_External_Port_Data_4, 632, sizeof(s_External_Port_Data_4) - 1, 2},
1050  {s_Registered_Instruction, 890, sizeof(s_Registered_Instruction) - 1, 1},
1051  {s_Status_Return_Level, 891, sizeof(s_Status_Return_Level) - 1, 1},
1052  {s_Hardware_Error_Status, 892, sizeof(s_Hardware_Error_Status) - 1, 1}};
1053 
1054 #define COUNT_PRO_ITEMS (sizeof(items_PRO) / sizeof(items_PRO[0]))
1055 
1056 static const ModelInfo info_PRO = {0.114,
1057  -2048,
1058  0,
1059  2048,
1060  -3.14159265,
1061  3.14159265};
1062 
1063 //---------------------------------------------------------
1064 // EXT PRO - All Other Pros...
1065 //---------------------------------------------------------
1066 static const ControlItem items_EXTPRO[]{
1067  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1068  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1069  {s_ID, 7, sizeof(s_ID) - 1, 1},
1070  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1071  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1072  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1073  {s_Homing_Offset, 13, sizeof(s_Homing_Offset) - 1, 4},
1074  {s_Moving_Threshold, 17, sizeof(s_Moving_Threshold) - 1, 4},
1075  {s_Temperature_Limit, 21, sizeof(s_Temperature_Limit) - 1, 1},
1076  {s_Max_Voltage_Limit, 22, sizeof(s_Max_Voltage_Limit) - 1, 2},
1077  {s_Min_Voltage_Limit, 24, sizeof(s_Min_Voltage_Limit) - 1, 2},
1078  {s_Acceleration_Limit, 26, sizeof(s_Acceleration_Limit) - 1, 4},
1079  {s_Torque_Limit, 30, sizeof(s_Torque_Limit) - 1, 2},
1080  {s_Velocity_Limit, 32, sizeof(s_Velocity_Limit) - 1, 4},
1081  {s_Max_Position_Limit, 36, sizeof(s_Max_Position_Limit) - 1, 4},
1082  {s_Min_Position_Limit, 40, sizeof(s_Min_Position_Limit) - 1, 4},
1083  {s_External_Port_Mode_1, 44, sizeof(s_External_Port_Mode_1) - 1, 1},
1084  {s_External_Port_Mode_2, 45, sizeof(s_External_Port_Mode_2) - 1, 1},
1085  {s_External_Port_Mode_3, 46, sizeof(s_External_Port_Mode_3) - 1, 1},
1086  {s_External_Port_Mode_4, 47, sizeof(s_External_Port_Mode_4) - 1, 1},
1087  {s_Shutdown, 48, sizeof(s_Shutdown) - 1, 1},
1088 
1089  {s_Torque_Enable, 562, sizeof(s_Torque_Enable) - 1, 1},
1090  {s_LED_RED, 563, sizeof(s_LED_RED) - 1, 1},
1091  {s_LED_GREEN, 564, sizeof(s_LED_GREEN) - 1, 1},
1092  {s_LED_BLUE, 565, sizeof(s_LED_BLUE) - 1, 1},
1093  {s_Velocity_I_Gain, 586, sizeof(s_Velocity_I_Gain) - 1, 2},
1094  {s_Velocity_P_Gain, 588, sizeof(s_Velocity_P_Gain) - 1, 2},
1095  {s_Position_P_Gain, 594, sizeof(s_Position_P_Gain) - 1, 2},
1096  {s_Goal_Position, 596, sizeof(s_Goal_Position) - 1, 4},
1097  {s_Goal_Velocity, 600, sizeof(s_Goal_Velocity) - 1, 4},
1098  {s_Goal_Torque, 604, sizeof(s_Goal_Torque) - 1, 2},
1099  {s_Goal_Acceleration, 606, sizeof(s_Goal_Acceleration) - 1, 4},
1100  {s_Moving, 610, sizeof(s_Moving) - 1, 1},
1101  {s_Present_Position, 611, sizeof(s_Present_Position) - 1, 4},
1102  {s_Present_Velocity, 615, sizeof(s_Present_Velocity) - 1, 4},
1103  {s_Present_Current, 621, sizeof(s_Present_Current) - 1, 2},
1104  {s_Present_Input_Voltage, 623, sizeof(s_Present_Input_Voltage) - 1, 2},
1105  {s_Present_Temperature, 625, sizeof(s_Present_Temperature) - 1, 1},
1106  {s_External_Port_Data_1, 626, sizeof(s_External_Port_Data_1) - 1, 2},
1107  {s_External_Port_Data_2, 628, sizeof(s_External_Port_Data_2) - 1, 2},
1108  {s_External_Port_Data_3, 630, sizeof(s_External_Port_Data_3) - 1, 2},
1109  {s_External_Port_Data_4, 632, sizeof(s_External_Port_Data_4) - 1, 2},
1110  {s_Registered_Instruction, 890, sizeof(s_Registered_Instruction) - 1, 1},
1111  {s_Status_Return_Level, 891, sizeof(s_Status_Return_Level) - 1, 1},
1112  {s_Hardware_Error_Status, 892, sizeof(s_Hardware_Error_Status) - 1, 1}};
1113 
1114 #define COUNT_EXTPRO_ITEMS (sizeof(items_EXTPRO) / sizeof(items_EXTPRO[0]))
1115 
1116 static const ModelInfo info_EXTPRO[] = {
1117  {0.00249657, -144197, 0, 144197, -3.14159265, 3.14159265}, // PRO_L54_30_S400_R
1118  {0.00199234, -180692, 0, 180692, -3.14159265, 3.14159265}, // PRO_L54_30_S500_R, PRO_L54_50_S500_R
1119  {0.00346667, -103846, 0, 103846, -3.14159265, 3.14159265}, // PRO_L54_50_S290_R
1120  {0.00389076, -131593, 0, 131593, -3.14159265, 3.14159265}, // PRO_M42_10_S260_R
1121  {0.00397746, -125708, 0, 125708, -3.14159265, 3.14159265}, // PRO_M54_40_S250_R, PRO_M54_60_S250_R
1122  {0.00329218, -151875, 0, 151875, -3.14159265, 3.14159265}, // PRO_H42_20_S300_R
1123  {0.00199234, -250961, 0, 250961, -3.14159265, 3.14159265}}; // PRO_H54_100_S500_R, PRO_H54_200_S500_R
1124 
1125 //---------------------------------------------------------
1126 // EXT PRO (A Firmware_Version)
1127 //---------------------------------------------------------
1129  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1130  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1131  {s_ID, 7, sizeof(s_ID) - 1, 1},
1132  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1133  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1134  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1135  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
1136  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
1137  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
1138  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
1139  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
1140  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
1141  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
1142  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
1143  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
1144  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
1145  {s_External_Port_Mode_1, 56, sizeof(s_External_Port_Mode_1) - 1, 1},
1146  {s_External_Port_Mode_2, 57, sizeof(s_External_Port_Mode_2) - 1, 1},
1147  {s_External_Port_Mode_3, 58, sizeof(s_External_Port_Mode_3) - 1, 1},
1148  {s_External_Port_Mode_4, 59, sizeof(s_External_Port_Mode_4) - 1, 1},
1149  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
1150 
1151  {s_Torque_Enable, 512, sizeof(s_Torque_Enable) - 1, 1},
1152  {s_LED_RED, 513, sizeof(s_LED_RED) - 1, 1},
1153  {s_LED_GREEN, 514, sizeof(s_LED_GREEN) - 1, 1},
1154  {s_LED_BLUE, 515, sizeof(s_LED_BLUE) - 1, 1},
1155  {s_Velocity_I_Gain, 524, sizeof(s_Velocity_I_Gain) - 1, 2},
1156  {s_Velocity_P_Gain, 526, sizeof(s_Velocity_P_Gain) - 1, 2},
1157  {s_Position_D_Gain, 528, sizeof(s_Position_D_Gain) - 1, 2},
1158  {s_Position_P_Gain, 532, sizeof(s_Position_P_Gain) - 1, 2},
1159  {s_Position_I_Gain, 530, sizeof(s_Position_I_Gain) - 1, 2},
1160  {s_Goal_Position, 564, sizeof(s_Goal_Position) - 1, 4},
1161  {s_Goal_Velocity, 552, sizeof(s_Goal_Velocity) - 1, 4},
1162  {s_Goal_Current, 604, sizeof(s_Goal_Current) - 1, 2},
1163  {s_Profile_Acceleration, 556, sizeof(s_Profile_Acceleration) - 1, 4},
1164  {s_Profile_Velocity, 560, sizeof(s_Profile_Velocity) - 1, 4},
1165  {s_Moving, 570, sizeof(s_Moving) - 1, 1},
1166  {s_Present_Position, 580, sizeof(s_Present_Position) - 1, 4},
1167  {s_Present_Velocity, 576, sizeof(s_Present_Velocity) - 1, 4},
1168  {s_Present_Current, 574, sizeof(s_Present_Current) - 1, 2},
1169  {s_Present_Input_Voltage, 592, sizeof(s_Present_Input_Voltage) - 1, 2},
1170  {s_Present_Temperature, 594, sizeof(s_Present_Temperature) - 1, 1},
1171  {s_External_Port_Data_1, 600, sizeof(s_External_Port_Data_1) - 1, 2},
1172  {s_External_Port_Data_2, 602, sizeof(s_External_Port_Data_2) - 1, 2},
1173  {s_External_Port_Data_3, 604, sizeof(s_External_Port_Data_3) - 1, 2},
1174  {s_External_Port_Data_4, 606, sizeof(s_External_Port_Data_4) - 1, 2}};
1175 
1176 #define COUNT_EXTPRO_A_ITEMS (sizeof(items_EXTPRO_A) / sizeof(items_EXTPRO_A[0]))
1177 
1178 static const ModelInfo info_EXTPRO_A[] = {
1179  {0.00389076, -131593, 0, 131593, -3.14159265, 3.14159265}, // PRO_M42_10_S260_R_A
1180  {0.00397746, -125708, 0, 125708, -3.14159265, 3.14159265}, // PRO_M54_40_S250_R_A, PRO_M54_60_S250_R_A
1181  {0.00329218, -151875, 0, 151875, -3.14159265, 3.14159265}, // PRO_H42_20_S300_R_A
1182  {0.00199234, -250961, 0, 250961, -3.14159265, 3.14159265}}; // PRO_H54_100_S500_R_A, PRO_H54_200_S500_R_A
1183 
1184 //---------------------------------------------------------
1185 // PRO PLUS - (num == PRO_H42P_020_S300_R, PRO_H54P_100_S500_R, PRO_H54P_200_S500_R)
1186 //---------------------------------------------------------
1188  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1189  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1190  {s_ID, 7, sizeof(s_ID) - 1, 1},
1191  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1192  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1193  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
1194  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1195  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
1196  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
1197  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
1198  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
1199  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
1200  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
1201  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
1202  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
1203  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
1204  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
1205  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
1206  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
1207  {s_External_Port_Mode_1, 56, sizeof(s_External_Port_Mode_1) - 1, 1},
1208  {s_External_Port_Mode_2, 57, sizeof(s_External_Port_Mode_2) - 1, 1},
1209  {s_External_Port_Mode_3, 58, sizeof(s_External_Port_Mode_3) - 1, 1},
1210  {s_External_Port_Mode_4, 59, sizeof(s_External_Port_Mode_4) - 1, 1},
1211  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
1212 
1213  {s_Torque_Enable, 512, sizeof(s_Torque_Enable) - 1, 1},
1214  {s_LED_RED, 513, sizeof(s_LED_RED) - 1, 1},
1215  {s_LED_GREEN, 514, sizeof(s_LED_GREEN) - 1, 1},
1216  {s_LED_BLUE, 515, sizeof(s_LED_BLUE) - 1, 1},
1217  {s_Status_Return_Level, 516, sizeof(s_Status_Return_Level) - 1, 1},
1218  {s_Registered_Instruction, 517, sizeof(s_Registered_Instruction) - 1, 1},
1219  {s_Hardware_Error_Status, 518, sizeof(s_Hardware_Error_Status) - 1, 1},
1220  {s_Velocity_I_Gain, 524, sizeof(s_Velocity_I_Gain) - 1, 2},
1221  {s_Velocity_P_Gain, 526, sizeof(s_Velocity_P_Gain) - 1, 2},
1222  {s_Position_D_Gain, 528, sizeof(s_Position_D_Gain) - 1, 2},
1223  {s_Position_I_Gain, 530, sizeof(s_Position_I_Gain) - 1, 2},
1224  {s_Position_P_Gain, 532, sizeof(s_Position_P_Gain) - 1, 2},
1225  {s_Feedforward_2nd_Gain, 536, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
1226  {s_Feedforward_1st_Gain, 538, sizeof(s_Feedforward_1st_Gain) - 1, 2},
1227  {s_Bus_Watchdog, 546, sizeof(s_Bus_Watchdog) - 1, 1},
1228  {s_Goal_PWM, 548, sizeof(s_Goal_PWM) - 1, 2},
1229  {s_Goal_Current, 550, sizeof(s_Goal_Current) - 1, 2},
1230  {s_Goal_Velocity, 552, sizeof(s_Goal_Velocity) - 1, 4},
1231  {s_Profile_Acceleration, 556, sizeof(s_Profile_Acceleration) - 1, 4},
1232  {s_Profile_Velocity, 560, sizeof(s_Profile_Velocity) - 1, 4},
1233  {s_Goal_Position, 564, sizeof(s_Goal_Position) - 1, 4},
1234  {s_Realtime_Tick, 568, sizeof(s_Realtime_Tick) - 1, 2},
1235  {s_Moving, 570, sizeof(s_Moving) - 1, 1},
1236  {s_Moving_Status, 571, sizeof(s_Moving) - 1, 1},
1237  {s_Present_PWM, 572, sizeof(s_Present_PWM) - 1, 2},
1238  {s_Present_Current, 574, sizeof(s_Present_Current) - 1, 2},
1239  {s_Present_Velocity, 576, sizeof(s_Present_Velocity) - 1, 4},
1240  {s_Present_Position, 580, sizeof(s_Present_Position) - 1, 4},
1241  {s_Velocity_Trajectory, 584, sizeof(s_Velocity_Trajectory) - 1, 4},
1242  {s_Position_Trajectory, 588, sizeof(s_Position_Trajectory) - 1, 4},
1243  {s_Present_Input_Voltage, 592, sizeof(s_Present_Input_Voltage) - 1, 2},
1244  {s_Present_Temperature, 594, sizeof(s_Present_Temperature) - 1, 1},
1245  {s_External_Port_Data_1, 600, sizeof(s_External_Port_Data_1) - 1, 2},
1246  {s_External_Port_Data_2, 602, sizeof(s_External_Port_Data_2) - 1, 2},
1247  {s_External_Port_Data_3, 604, sizeof(s_External_Port_Data_3) - 1, 2},
1248  {s_External_Port_Data_4, 606, sizeof(s_External_Port_Data_4) - 1, 2}};
1249 
1250 #define COUNT_EXTPRO_PLUS_ITEMS (sizeof(items_PRO_PLUS) / sizeof(items_PRO_PLUS[0]))
1251 
1252 static const ModelInfo info_PRO_PLUS[] = {
1253  {0.01, -251173, 0, 251173, -3.14159265, 3.14159265}, // PRO_PLUS_M42P_010_S260_R
1254  {0.01, -251173, 0, 251173, -3.14159265, 3.14159265}, // PRO_PLUS_M54P_040_S250_R
1255  {0.01, -262931, 0, 262931, -3.14159265, 3.14159265}, // PRO_PLUS_M54P_060_S250_R
1256  {0.01, -303454, 0, 303454, -3.14159265, 3.14159265}, // PRO_PLUS_H42P_020_S300_R
1257  {0.01, -501433, 0, 501433, -3.14159265, 3.14159265}, // PRO_PLUS_H54P_100_S500_R
1258  {0.01, -501433, 0, 501433, -3.14159265, 3.14159265}}; // PRO_PLUS_H54P_200_S500_R
1259 
1260 //---------------------------------------------------------
1261 // Gripper - (num == RH_P12_RN)
1262 //---------------------------------------------------------
1264  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1265  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1266  {s_ID, 7, sizeof(s_ID) - 1, 1},
1267  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1268  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1269  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1270  {s_Homing_Offset, 13, sizeof(s_Homing_Offset) - 1, 4},
1271  {s_Moving_Threshold, 17, sizeof(s_Moving_Threshold) - 1, 4},
1272  {s_Temperature_Limit, 21, sizeof(s_Temperature_Limit) - 1, 1},
1273  {s_Max_Voltage_Limit, 22, sizeof(s_Max_Voltage_Limit) - 1, 2},
1274  {s_Min_Voltage_Limit, 24, sizeof(s_Min_Voltage_Limit) - 1, 2},
1275  {s_Acceleration_Limit, 26, sizeof(s_Acceleration_Limit) - 1, 4},
1276  {s_Torque_Limit, 30, sizeof(s_Torque_Limit) - 1, 2},
1277  {s_Velocity_Limit, 32, sizeof(s_Velocity_Limit) - 1, 4},
1278  {s_Max_Position_Limit, 36, sizeof(s_Max_Position_Limit) - 1, 4},
1279  {s_Min_Position_Limit, 40, sizeof(s_Min_Position_Limit) - 1, 4},
1280  {s_External_Port_Mode_1, 44, sizeof(s_External_Port_Mode_1) - 1, 1},
1281  {s_External_Port_Mode_2, 45, sizeof(s_External_Port_Mode_2) - 1, 1},
1282  {s_External_Port_Mode_3, 46, sizeof(s_External_Port_Mode_3) - 1, 1},
1283  {s_External_Port_Mode_4, 47, sizeof(s_External_Port_Mode_4) - 1, 1},
1284  {s_Shutdown, 48, sizeof(s_Shutdown) - 1, 1},
1285 
1286  {s_Torque_Enable, 562, sizeof(s_Torque_Enable) - 1, 1},
1287  {s_LED_RED, 563, sizeof(s_LED_RED) - 1, 1},
1288  {s_LED_GREEN, 564, sizeof(s_LED_GREEN) - 1, 1},
1289  {s_LED_BLUE, 565, sizeof(s_LED_BLUE) - 1, 1},
1290  {s_Velocity_I_Gain, 586, sizeof(s_Velocity_I_Gain) - 1, 2},
1291  {s_Velocity_P_Gain, 588, sizeof(s_Velocity_P_Gain) - 1, 2},
1292  {s_Position_P_Gain, 594, sizeof(s_Position_P_Gain) - 1, 2},
1293  {s_Goal_Position, 596, sizeof(s_Goal_Position) - 1, 4},
1294  {s_Goal_Velocity, 600, sizeof(s_Goal_Velocity) - 1, 4},
1295  {s_Goal_Torque, 604, sizeof(s_Goal_Torque) - 1, 2},
1296  {s_Goal_Acceleration, 606, sizeof(s_Goal_Acceleration) - 1, 4},
1297  {s_Moving, 610, sizeof(s_Moving) - 1, 1},
1298  {s_Present_Position, 611, sizeof(s_Present_Position) - 1, 4},
1299  {s_Present_Velocity, 615, sizeof(s_Present_Velocity) - 1, 4},
1300  {s_Present_Current, 621, sizeof(s_Present_Current) - 1, 2},
1301  {s_Present_Input_Voltage, 623, sizeof(s_Present_Input_Voltage) - 1, 2},
1302  {s_Present_Temperature, 625, sizeof(s_Present_Temperature) - 1, 1},
1303  {s_External_Port_Data_1, 626, sizeof(s_External_Port_Data_1) - 1, 2},
1304  {s_External_Port_Data_2, 628, sizeof(s_External_Port_Data_2) - 1, 2},
1305  {s_External_Port_Data_3, 630, sizeof(s_External_Port_Data_3) - 1, 2},
1306  {s_External_Port_Data_4, 632, sizeof(s_External_Port_Data_4) - 1, 2},
1307  {s_Registered_Instruction, 890, sizeof(s_Registered_Instruction) - 1, 1},
1308  {s_Status_Return_Level, 891, sizeof(s_Status_Return_Level) - 1, 1},
1309  {s_Hardware_Error_Status, 892, sizeof(s_Hardware_Error_Status) - 1, 1}};
1310 #define COUNT_Gripper_ITEMS (sizeof(items_Gripper) / sizeof(items_Gripper[0]))
1311 
1312 static const ModelInfo info_Gripper = {0.01,
1313  0,
1314  0,
1315  1150,
1316  0,
1317  1.7631835937};
1318 
1319 //---------------------------------------------------------
1320 // Gripper A Firmware - (num == RH_P12_RN_A)
1321 //---------------------------------------------------------
1323  {s_Model_Number, 0, sizeof(s_Model_Number) - 1, 2},
1324  {s_Firmware_Version, 6, sizeof(s_Firmware_Version) - 1, 1},
1325  {s_ID, 7, sizeof(s_ID) - 1, 1},
1326  {s_Baud_Rate, 8, sizeof(s_Baud_Rate) - 1, 1},
1327  {s_Return_Delay_Time, 9, sizeof(s_Return_Delay_Time) - 1, 1},
1328  {s_Drive_Mode, 10, sizeof(s_Drive_Mode) - 1, 1},
1329  {s_Operating_Mode, 11, sizeof(s_Operating_Mode) - 1, 1},
1330  {s_Secondary_ID, 12, sizeof(s_Secondary_ID) - 1, 1},
1331  {s_Homing_Offset, 20, sizeof(s_Homing_Offset) - 1, 4},
1332  {s_Moving_Threshold, 24, sizeof(s_Moving_Threshold) - 1, 4},
1333  {s_Temperature_Limit, 31, sizeof(s_Temperature_Limit) - 1, 1},
1334  {s_Max_Voltage_Limit, 32, sizeof(s_Max_Voltage_Limit) - 1, 2},
1335  {s_Min_Voltage_Limit, 34, sizeof(s_Min_Voltage_Limit) - 1, 2},
1336  {s_PWM_Limit, 36, sizeof(s_PWM_Limit) - 1, 2},
1337  {s_Current_Limit, 38, sizeof(s_Current_Limit) - 1, 2},
1338  {s_Acceleration_Limit, 40, sizeof(s_Acceleration_Limit) - 1, 4},
1339  {s_Velocity_Limit, 44, sizeof(s_Velocity_Limit) - 1, 4},
1340  {s_Max_Position_Limit, 48, sizeof(s_Max_Position_Limit) - 1, 4},
1341  {s_Min_Position_Limit, 52, sizeof(s_Min_Position_Limit) - 1, 4},
1342  {s_External_Port_Mode_1, 56, sizeof(s_External_Port_Mode_1) - 1, 1},
1343  {s_External_Port_Mode_2, 57, sizeof(s_External_Port_Mode_2) - 1, 1},
1344  {s_External_Port_Mode_3, 58, sizeof(s_External_Port_Mode_3) - 1, 1},
1345  {s_External_Port_Mode_4, 59, sizeof(s_External_Port_Mode_4) - 1, 1},
1346  {s_Shutdown, 63, sizeof(s_Shutdown) - 1, 1},
1347 
1348  {s_Torque_Enable, 512, sizeof(s_Torque_Enable) - 1, 1},
1349  {s_LED_RED, 513, sizeof(s_LED_RED) - 1, 1},
1350  {s_LED_GREEN, 514, sizeof(s_LED_GREEN) - 1, 1},
1351  {s_LED_BLUE, 515, sizeof(s_LED_BLUE) - 1, 1},
1352  {s_Status_Return_Level, 516, sizeof(s_Status_Return_Level) - 1, 1},
1353  {s_Registered_Instruction, 517, sizeof(s_Registered_Instruction) - 1, 1},
1354  {s_Hardware_Error_Status, 518, sizeof(s_Hardware_Error_Status) - 1, 1},
1355  {s_Velocity_I_Gain, 524, sizeof(s_Velocity_I_Gain) - 1, 2},
1356  {s_Velocity_P_Gain, 526, sizeof(s_Velocity_P_Gain) - 1, 2},
1357  {s_Position_D_Gain, 528, sizeof(s_Position_D_Gain) - 1, 2},
1358  {s_Position_I_Gain, 530, sizeof(s_Position_I_Gain) - 1, 2},
1359  {s_Position_P_Gain, 532, sizeof(s_Position_P_Gain) - 1, 2},
1360  {s_Feedforward_2nd_Gain, 536, sizeof(s_Feedforward_2nd_Gain) - 1, 2},
1361  {s_Feedforward_1st_Gain, 538, sizeof(s_Feedforward_1st_Gain) - 1, 2},
1362  {s_Bus_Watchdog, 546, sizeof(s_Bus_Watchdog) - 1, 1},
1363  {s_Goal_PWM, 548, sizeof(s_Goal_PWM) - 1, 2},
1364  {s_Goal_Current, 550, sizeof(s_Goal_Current) - 1, 2},
1365  {s_Goal_Velocity, 552, sizeof(s_Goal_Velocity) - 1, 4},
1366  {s_Profile_Acceleration, 556, sizeof(s_Profile_Acceleration) - 1, 4},
1367  {s_Profile_Velocity, 560, sizeof(s_Profile_Velocity) - 1, 4},
1368  {s_Goal_Position, 564, sizeof(s_Goal_Position) - 1, 4},
1369  {s_Realtime_Tick, 568, sizeof(s_Realtime_Tick) - 1, 2},
1370  {s_Moving, 570, sizeof(s_Moving) - 1, 1},
1371  {s_Moving_Status, 571, sizeof(s_Moving) - 1, 1},
1372  {s_Present_PWM, 572, sizeof(s_Present_PWM) - 1, 2},
1373  {s_Present_Current, 574, sizeof(s_Present_Current) - 1, 2},
1374  {s_Present_Velocity, 576, sizeof(s_Present_Velocity) - 1, 4},
1375  {s_Present_Position, 580, sizeof(s_Present_Position) - 1, 4},
1376  {s_Velocity_Trajectory, 584, sizeof(s_Velocity_Trajectory) - 1, 4},
1377  {s_Position_Trajectory, 588, sizeof(s_Position_Trajectory) - 1, 4},
1378  {s_Present_Input_Voltage, 592, sizeof(s_Present_Input_Voltage) - 1, 2},
1379  {s_Present_Temperature, 594, sizeof(s_Present_Temperature) - 1, 1},
1380  {s_External_Port_Data_1, 600, sizeof(s_External_Port_Data_1) - 1, 2},
1381  {s_External_Port_Data_2, 602, sizeof(s_External_Port_Data_2) - 1, 2},
1382  {s_External_Port_Data_3, 604, sizeof(s_External_Port_Data_3) - 1, 2},
1383  {s_External_Port_Data_4, 606, sizeof(s_External_Port_Data_4) - 1, 2}};
1384 #define COUNT_EXTGripper_ITEMS (sizeof(items_EXTGripper) / sizeof(items_EXTGripper[0]))
1385 
1386 static const ModelInfo info_EXTGripper = {0.01,
1387  0,
1388  0,
1389  1150,
1390  0,
1391  1.7631835937};
1392 
1393 //=========================================================
1394 // Get Servo control table for the specified servo type
1395 //=========================================================
1396 static uint8_t the_number_of_item = 0;
1397 const ControlItem *DynamixelItem::getControlTable(uint16_t model_number)
1398 {
1399  uint16_t num = model_number;
1400 
1401  const ControlItem *control_table;
1402  if (num == AX_12A || num == AX_12W || num == AX_18A)
1403  {
1404  control_table = items_AX;
1406  }
1407  else if (num == RX_10 || num == RX_24F || num == RX_28 || num == RX_64)
1408  {
1409  control_table = items_RX;
1411  }
1412  else if (num == EX_106)
1413  {
1414  control_table = items_EX;
1416  }
1417  else if (num == MX_12W || num == MX_28)
1418  {
1419  control_table = items_MX;
1421  }
1422  else if (num == MX_64 || num == MX_106)
1423  {
1424  control_table = items_EXTMX;
1426  }
1427  else if (num == MX_28_2)
1428  {
1429  control_table = items_MX2;
1431  }
1432  else if (num == MX_64_2 || num == MX_106_2)
1433  {
1434  control_table = items_EXTMX2;
1436  }
1437  else if (num == XL_320)
1438  {
1439  control_table = items_XL320;
1441  }
1442  else if (num == XL330_M077 || num == XL330_M288)
1443  {
1444  control_table = items_XL330;
1446  }
1447  else if (num == XL430_W250 || num == XL430_W250_2 || num == XC430_W150 || num == XC430_W240 || num == XC430_W250_2)
1448  {
1449  control_table = items_XL;
1451  }
1452  else if (num == XM430_W210 || num == XM430_W350)
1453  {
1454  control_table = items_XM;
1456  }
1457  else if (num == XM540_W150 || num == XM540_W270)
1458  {
1459  control_table = items_EXTXM;
1461  }
1462  else if (num == XH430_V210 || num == XH430_V350 || num == XH430_W210 || num == XH430_W350)
1463  {
1464  control_table = items_XH;
1466  }
1467  else if (num == XH540_W150 || num == XH540_W270 || num == XH540_V150 || num == XH540_V270)
1468  {
1469  control_table = items_EXTXH;
1471  }
1472  else if (num == XW540_T260 || num == XW540_T140)
1473  {
1474  control_table = items_XW;
1476  }
1477  else if (num == PRO_L42_10_S300_R)
1478  {
1479  control_table = items_PRO;
1481  }
1482  else if (num == PRO_L54_30_S400_R || num == PRO_L54_30_S500_R || num == PRO_L54_50_S290_R || num == PRO_L54_50_S500_R ||
1483  num == PRO_M42_10_S260_R || num == PRO_M54_40_S250_R || num == PRO_M54_60_S250_R ||
1484  num == PRO_H42_20_S300_R || num == PRO_H54_100_S500_R || num == PRO_H54_200_S500_R)
1485  {
1486  control_table = items_EXTPRO;
1488  }
1489  else if (num == PRO_M42_10_S260_R_A || num == PRO_M54_40_S250_R_A || num == PRO_M54_60_S250_R_A ||
1491  {
1492  control_table = items_EXTPRO_A;
1494  }
1495  else if (num == PRO_PLUS_M42P_010_S260_R || num == PRO_PLUS_M54P_040_S250_R || num == PRO_PLUS_M54P_060_S250_R ||
1497  {
1498  control_table = items_PRO_PLUS;
1500  }
1501  else if (num == RH_P12_RN)
1502  {
1503  control_table = items_Gripper;
1505  }
1506  else if (num == RH_P12_RN_A)
1507  {
1508  control_table = items_EXTGripper;
1510  }
1511  else
1512  {
1513  control_table = NULL;
1514  the_number_of_item = 0;
1515  }
1516 
1517  return control_table;
1518 }
1519 
1520 const ModelInfo *DynamixelItem::getModelInfo(uint16_t model_number)
1521 {
1522  uint16_t num = model_number;
1523 
1524  const ModelInfo *info;
1525 
1526  if (num == AX_12A || num == AX_12W || num == AX_18A)
1527  {
1528  info = &info_AX;
1529  }
1530  else if (num == RX_10 || num == RX_24F || num == RX_28 || num == RX_64)
1531  {
1532  info = &info_RX;
1533  }
1534  else if (num == EX_106)
1535  {
1536  info = &info_EX;
1537  }
1538  else if (num == MX_12W || num == MX_28)
1539  {
1540  info = &info_MX;
1541  }
1542  else if (num == MX_64 || num == MX_106)
1543  {
1544  info = &info_EXTMX;
1545  }
1546  else if (num == MX_28_2)
1547  {
1548  info = &info_MX2;
1549  }
1550  else if (num == MX_64_2 || num == MX_106_2)
1551  {
1552  info = &info_EXTMX2;
1553  }
1554  else if (num == XL_320)
1555  {
1556  info = &info_XL320;
1557  }
1558  else if (num == XL330_M077 || num == XL330_M288)
1559  {
1560  info = &info_XL330;
1561  }
1562  else if (num == XL430_W250 || num == XL430_W250_2 || num == XC430_W150 || num == XC430_W240 || num == XC430_W250_2)
1563  {
1564  info = &info_XL;
1565  }
1566  else if (num == XM430_W210 || num == XM430_W350)
1567  {
1568  info = &info_XM;
1569  }
1570  else if (num == XM540_W150 || num == XM540_W270)
1571  {
1572  info = &info_EXTXM;
1573  }
1574  else if (num == XH430_V210 || num == XH430_V350 || num == XH430_W210 || num == XH430_W350)
1575  {
1576  info = &info_XH;
1577  }
1578  else if (num == XH540_W150 || num == XH540_W270 || num == XH540_V150 || num == XH540_V270)
1579  {
1580  info = &info_EXTXH;
1581  }
1582  else if (num == XW540_T260 || num == XW540_T140)
1583  {
1584  info = &info_XW;
1585  }
1586  else if (num == PRO_L42_10_S300_R)
1587  {
1588  info = &info_PRO;
1589  }
1590  else if (num == PRO_L54_30_S400_R)
1591  {
1592  info = &info_EXTPRO[0];
1593  }
1594  else if (num == PRO_L54_30_S500_R || num == PRO_L54_50_S500_R)
1595  {
1596  info = &info_EXTPRO[1];
1597  }
1598  else if (num == PRO_L54_50_S290_R)
1599  {
1600  info = &info_EXTPRO[2];
1601  }
1602  else if (num == PRO_M42_10_S260_R)
1603  {
1604  info = &info_EXTPRO[3];
1605  }
1606  else if (num == PRO_M54_40_S250_R || num == PRO_M54_60_S250_R)
1607  {
1608  info = &info_EXTPRO[4];
1609  }
1610  else if (num == PRO_H42_20_S300_R)
1611  {
1612  info = &info_EXTPRO[5];
1613  }
1614  else if (num == PRO_H54_100_S500_R || num == PRO_H54_200_S500_R)
1615  {
1616  info = &info_EXTPRO[6];
1617  }
1618  else if (num == PRO_M42_10_S260_R_A)
1619  {
1620  info = &info_EXTPRO_A[0];
1621  }
1622  else if (num == PRO_M54_40_S250_R_A || num == PRO_M54_60_S250_R_A)
1623  {
1624  info = &info_EXTPRO_A[1];
1625  }
1626  else if (num == PRO_H42_20_S300_R_A)
1627  {
1628  info = &info_EXTPRO_A[2];
1629  }
1630  else if (num == PRO_H54_100_S500_R_A || num == PRO_H54_200_S500_R_A)
1631  {
1632  info = &info_EXTPRO_A[3];
1633  }
1634  else if (num == PRO_PLUS_M42P_010_S260_R)
1635  {
1636  info = &info_PRO_PLUS[0];
1637  }
1638  else if (num == PRO_PLUS_M54P_040_S250_R)
1639  {
1640  info = &info_PRO_PLUS[1];
1641  }
1642  else if (num == PRO_PLUS_M54P_060_S250_R)
1643  {
1644  info = &info_PRO_PLUS[2];
1645  }
1646  else if (num == PRO_PLUS_H42P_020_S300_R)
1647  {
1648  info = &info_PRO_PLUS[3];
1649  }
1650  else if (num == PRO_PLUS_H54P_100_S500_R)
1651  {
1652  info = &info_PRO_PLUS[4];
1653  }
1654  else if (num == PRO_PLUS_H54P_200_S500_R)
1655  {
1656  info = &info_PRO_PLUS[5];
1657  }
1658  else if (num == RH_P12_RN)
1659  {
1660  info = &info_Gripper;
1661  }
1662  else if (num == RH_P12_RN_A)
1663  {
1664  info = &info_EXTGripper;
1665  }
1666  else
1667  {
1668  info = NULL;
1669  }
1670 
1671  return info;
1672 }
1673 
1675 {
1676  return the_number_of_item;
1677 }
s_Baud_Rate
static const char s_Baud_Rate[]
Definition: dynamixel_item.cpp:29
XM430_W350
#define XM430_W350
Definition: dynamixel_item.h:58
RX_64
#define RX_64
Definition: dynamixel_item.h:32
items_EXTPRO
static const ControlItem items_EXTPRO[]
Definition: dynamixel_item.cpp:1066
s_Status_Return_Level
static const char s_Status_Return_Level[]
Definition: dynamixel_item.cpp:109
s_Return_Delay_Time
static const char s_Return_Delay_Time[]
Definition: dynamixel_item.cpp:105
s_Sensored_Current
static const char s_Sensored_Current[]
Definition: dynamixel_item.cpp:107
s_Registered_Instruction
static const char s_Registered_Instruction[]
Definition: dynamixel_item.cpp:103
s_Feedforward_1st_Gain
static const char s_Feedforward_1st_Gain[]
Definition: dynamixel_item.cpp:50
info_XH
static const ModelInfo info_XH
Definition: dynamixel_item.cpp:866
s_Present_Current
static const char s_Present_Current[]
Definition: dynamixel_item.cpp:85
info_XL
static const ModelInfo info_XL
Definition: dynamixel_item.cpp:662
s_Profile_Acceleration
static const char s_Profile_Acceleration[]
Definition: dynamixel_item.cpp:95
items_MX2
static const ControlItem items_MX2[]
Definition: dynamixel_item.cpp:315
MX_28
#define MX_28
Definition: dynamixel_item.h:37
info_Gripper
static const ModelInfo info_Gripper
Definition: dynamixel_item.cpp:1312
the_number_of_item
static uint8_t the_number_of_item
Definition: dynamixel_item.cpp:1396
s_Position_Trajectory
static const char s_Position_Trajectory[]
Definition: dynamixel_item.cpp:84
info_PRO_PLUS
static const ModelInfo info_PRO_PLUS[]
Definition: dynamixel_item.cpp:1252
info_EXTMX2
static const ModelInfo info_EXTMX2
Definition: dynamixel_item.cpp:487
s_Protocol_Version
static const char s_Protocol_Version[]
Definition: dynamixel_item.cpp:97
XL330_M288
#define XL330_M288
Definition: dynamixel_item.h:47
s_Present_Voltage
static const char s_Present_Voltage[]
Definition: dynamixel_item.cpp:94
s_Position_D_Gain
static const char s_Position_D_Gain[]
Definition: dynamixel_item.cpp:81
s_Firmware_Version
static const char s_Firmware_Version[]
Definition: dynamixel_item.cpp:52
items_EXTMX2
static const ControlItem items_EXTMX2[]
Definition: dynamixel_item.cpp:431
DynamixelItem::getControlTable
const ControlItem * getControlTable(uint16_t model_number)
Definition: dynamixel_item.cpp:1397
items_XL
static const ControlItem items_XL[]
Definition: dynamixel_item.cpp:608
s_Multi_Turn_Offset
static const char s_Multi_Turn_Offset[]
Definition: dynamixel_item.cpp:78
RX_10
#define RX_10
Definition: dynamixel_item.h:29
COUNT_EXTPRO_PLUS_ITEMS
#define COUNT_EXTPRO_PLUS_ITEMS
Definition: dynamixel_item.cpp:1250
PRO_PLUS_M54P_060_S250_R
#define PRO_PLUS_M54P_060_S250_R
Definition: dynamixel_item.h:100
s_Velocity_Limit
static const char s_Velocity_Limit[]
Definition: dynamixel_item.cpp:115
s_Goal_Current
static const char s_Goal_Current[]
Definition: dynamixel_item.cpp:54
s_Goal_Acceleration
static const char s_Goal_Acceleration[]
Definition: dynamixel_item.cpp:53
info_EXTGripper
static const ModelInfo info_EXTGripper
Definition: dynamixel_item.cpp:1386
XL_320
#define XL_320
Definition: dynamixel_item.h:44
info_AX
static const ModelInfo info_AX
Definition: dynamixel_item.cpp:160
PRO_H42_20_S300_R_A
#define PRO_H42_20_S300_R_A
Definition: dynamixel_item.h:94
info_XL330
static const ModelInfo info_XL330
Definition: dynamixel_item.cpp:598
PRO_H54_100_S500_R
#define PRO_H54_100_S500_R
Definition: dynamixel_item.h:87
s_Alarm_LED
static const char s_Alarm_LED[]
Definition: dynamixel_item.cpp:28
PRO_PLUS_H54P_100_S500_R
#define PRO_PLUS_H54P_100_S500_R
Definition: dynamixel_item.h:103
s_Min_Position_Limit
static const char s_Min_Position_Limit[]
Definition: dynamixel_item.cpp:71
items_EX
static const ControlItem items_EX[]
Definition: dynamixel_item.cpp:217
XH540_V150
#define XH540_V150
Definition: dynamixel_item.h:70
info_XM
static const ModelInfo info_XM
Definition: dynamixel_item.cpp:728
items_XL330
static const ControlItem items_XL330[]
Definition: dynamixel_item.cpp:543
DynamixelItem::getModelInfo
const ModelInfo * getModelInfo(uint16_t model_number)
Definition: dynamixel_item.cpp:1520
s_Current_Limit
static const char s_Current_Limit[]
Definition: dynamixel_item.cpp:36
s_Torque_Control_Mode_Enable
static const char s_Torque_Control_Mode_Enable[]
Definition: dynamixel_item.cpp:111
s_Velocity_P_Gain
static const char s_Velocity_P_Gain[]
Definition: dynamixel_item.cpp:116
COUNT_MX2_ITEMS
#define COUNT_MX2_ITEMS
Definition: dynamixel_item.cpp:367
s_ID
static const char s_ID[]
Definition: dynamixel_item.cpp:62
PRO_L54_30_S400_R
#define PRO_L54_30_S400_R
Definition: dynamixel_item.h:77
MX_12W
#define MX_12W
Definition: dynamixel_item.h:36
AX_12W
#define AX_12W
Definition: dynamixel_item.h:26
RH_P12_RN_A
#define RH_P12_RN_A
Definition: dynamixel_item.h:107
COUNT_EXTMX2_ITEMS
#define COUNT_EXTMX2_ITEMS
Definition: dynamixel_item.cpp:485
XW540_T260
#define XW540_T260
Definition: dynamixel_item.h:73
items_EXTXM
static const ControlItem items_EXTXM[]
Definition: dynamixel_item.cpp:738
items_XL320
static const ControlItem items_XL320[]
Definition: dynamixel_item.cpp:497
XH540_W150
#define XH540_W150
Definition: dynamixel_item.h:68
s_Operating_Mode
static const char s_Operating_Mode[]
Definition: dynamixel_item.cpp:79
s_Secondary_ID
static const char s_Secondary_ID[]
Definition: dynamixel_item.cpp:106
s_CCW_Compliance_Margin
static const char s_CCW_Compliance_Margin[]
Definition: dynamixel_item.cpp:32
s_Current
static const char s_Current[]
Definition: dynamixel_item.cpp:35
s_Goal_PWM
static const char s_Goal_PWM[]
Definition: dynamixel_item.cpp:56
AX_18A
#define AX_18A
Definition: dynamixel_item.h:27
DynamixelItem::getTheNumberOfControlItem
uint8_t getTheNumberOfControlItem()
Definition: dynamixel_item.cpp:1674
items_EXTXH
static const ControlItem items_EXTXH[]
Definition: dynamixel_item.cpp:876
XM430_W210
#define XM430_W210
Definition: dynamixel_item.h:57
items_Gripper
static const ControlItem items_Gripper[]
Definition: dynamixel_item.cpp:1263
COUNT_EXTPRO_ITEMS
#define COUNT_EXTPRO_ITEMS
Definition: dynamixel_item.cpp:1114
s_External_Port_Data_3
static const char s_External_Port_Data_3[]
Definition: dynamixel_item.cpp:48
info_RX
static const ModelInfo info_RX
Definition: dynamixel_item.cpp:207
s_Homing_Offset
static const char s_Homing_Offset[]
Definition: dynamixel_item.cpp:60
XH430_W350
#define XH430_W350
Definition: dynamixel_item.h:64
PRO_M42_10_S260_R
#define PRO_M42_10_S260_R
Definition: dynamixel_item.h:82
PRO_H54_200_S500_R_A
#define PRO_H54_200_S500_R_A
Definition: dynamixel_item.h:96
COUNT_AX_ITEMS
#define COUNT_AX_ITEMS
Definition: dynamixel_item.cpp:158
info_EXTXH
static const ModelInfo info_EXTXH
Definition: dynamixel_item.cpp:932
s_Moving_Speed
static const char s_Moving_Speed[]
Definition: dynamixel_item.cpp:75
s_Control_Mode
static const char s_Control_Mode[]
Definition: dynamixel_item.cpp:34
s_External_Port_Mode_2
static const char s_External_Port_Mode_2[]
Definition: dynamixel_item.cpp:43
COUNT_XW_ITEMS
#define COUNT_XW_ITEMS
Definition: dynamixel_item.cpp:995
s_CW_Compliance_Margin
static const char s_CW_Compliance_Margin[]
Definition: dynamixel_item.cpp:38
s_Lock
static const char s_Lock[]
Definition: dynamixel_item.cpp:67
s_I_gain
static const char s_I_gain[]
Definition: dynamixel_item.cpp:61
s_Present_Load
static const char s_Present_Load[]
Definition: dynamixel_item.cpp:88
RH_P12_RN
#define RH_P12_RN
Definition: dynamixel_item.h:106
PRO_PLUS_M54P_040_S250_R
#define PRO_PLUS_M54P_040_S250_R
Definition: dynamixel_item.h:99
PRO_M42_10_S260_R_A
#define PRO_M42_10_S260_R_A
Definition: dynamixel_item.h:90
s_PWM_Limit
static const char s_PWM_Limit[]
Definition: dynamixel_item.cpp:99
PRO_M54_60_S250_R
#define PRO_M54_60_S250_R
Definition: dynamixel_item.h:84
PRO_H54_100_S500_R_A
#define PRO_H54_100_S500_R_A
Definition: dynamixel_item.h:95
s_Goal_Velocity
static const char s_Goal_Velocity[]
Definition: dynamixel_item.cpp:58
s_External_Port_Data_4
static const char s_External_Port_Data_4[]
Definition: dynamixel_item.cpp:49
s_Velocity_Trajectory
static const char s_Velocity_Trajectory[]
Definition: dynamixel_item.cpp:117
info_EXTPRO
static const ModelInfo info_EXTPRO[]
Definition: dynamixel_item.cpp:1116
info_XW
static const ModelInfo info_XW
Definition: dynamixel_item.cpp:997
s_External_Port_Data_2
static const char s_External_Port_Data_2[]
Definition: dynamixel_item.cpp:47
XC430_W250_2
#define XC430_W250_2
Definition: dynamixel_item.h:52
s_Profile_Velocity
static const char s_Profile_Velocity[]
Definition: dynamixel_item.cpp:96
XM540_W150
#define XM540_W150
Definition: dynamixel_item.h:60
PRO_M54_60_S250_R_A
#define PRO_M54_60_S250_R_A
Definition: dynamixel_item.h:92
PRO_H54_200_S500_R
#define PRO_H54_200_S500_R
Definition: dynamixel_item.h:88
s_Feedforward_2nd_Gain
static const char s_Feedforward_2nd_Gain[]
Definition: dynamixel_item.cpp:51
items_MX
static const ControlItem items_MX[]
Definition: dynamixel_item.cpp:266
COUNT_XH_ITEMS
#define COUNT_XH_ITEMS
Definition: dynamixel_item.cpp:864
XH430_V210
#define XH430_V210
Definition: dynamixel_item.h:65
XC430_W240
#define XC430_W240
Definition: dynamixel_item.h:55
s_Acceleration_Limit
static const char s_Acceleration_Limit[]
Definition: dynamixel_item.cpp:27
items_XM
static const ControlItem items_XM[]
Definition: dynamixel_item.cpp:672
s_Present_Input
static const char s_Present_Input[]
Definition: dynamixel_item.cpp:86
s_Registered
static const char s_Registered[]
Definition: dynamixel_item.cpp:102
items_EXTMX
static const ControlItem items_EXTMX[]
Definition: dynamixel_item.cpp:379
s_CCW_Compliance_Slope
static const char s_CCW_Compliance_Slope[]
Definition: dynamixel_item.cpp:33
ModelInfo
Definition: dynamixel_item.h:121
items_XW
static const ControlItem items_XW[]
Definition: dynamixel_item.cpp:942
s_CW_Compliance_Slope
static const char s_CW_Compliance_Slope[]
Definition: dynamixel_item.cpp:39
XL430_W250
#define XL430_W250
Definition: dynamixel_item.h:49
items_PRO
static const ControlItem items_PRO[]
Definition: dynamixel_item.cpp:1007
COUNT_XM_ITEMS
#define COUNT_XM_ITEMS
Definition: dynamixel_item.cpp:726
s_External_Port_Mode_4
static const char s_External_Port_Mode_4[]
Definition: dynamixel_item.cpp:45
MX_106_2
#define MX_106_2
Definition: dynamixel_item.h:42
s_Realtime_Tick
static const char s_Realtime_Tick[]
Definition: dynamixel_item.cpp:101
s_Resolution_Divider
static const char s_Resolution_Divider[]
Definition: dynamixel_item.cpp:104
s_Max_Voltage_Limit
static const char s_Max_Voltage_Limit[]
Definition: dynamixel_item.cpp:70
info_MX2
static const ModelInfo info_MX2
Definition: dynamixel_item.cpp:369
XH540_V270
#define XH540_V270
Definition: dynamixel_item.h:71
s_CW_Angle_Limit
static const char s_CW_Angle_Limit[]
Definition: dynamixel_item.cpp:37
s_Moving
static const char s_Moving[]
Definition: dynamixel_item.cpp:74
s_Max_Position_Limit
static const char s_Max_Position_Limit[]
Definition: dynamixel_item.cpp:68
s_Present_Speed
static const char s_Present_Speed[]
Definition: dynamixel_item.cpp:91
PRO_PLUS_H42P_020_S300_R
#define PRO_PLUS_H42P_020_S300_R
Definition: dynamixel_item.h:102
PRO_L54_50_S500_R
#define PRO_L54_50_S500_R
Definition: dynamixel_item.h:80
PRO_H42_20_S300_R
#define PRO_H42_20_S300_R
Definition: dynamixel_item.h:86
XL330_M077
#define XL330_M077
Definition: dynamixel_item.h:46
XC430_W150
#define XC430_W150
Definition: dynamixel_item.h:54
info_EXTPRO_A
static const ModelInfo info_EXTPRO_A[]
Definition: dynamixel_item.cpp:1178
s_Torque_Enable
static const char s_Torque_Enable[]
Definition: dynamixel_item.cpp:112
s_D_gain
static const char s_D_gain[]
Definition: dynamixel_item.cpp:40
XL430_W250_2
#define XL430_W250_2
Definition: dynamixel_item.h:51
PRO_M54_40_S250_R_A
#define PRO_M54_40_S250_R_A
Definition: dynamixel_item.h:91
XH430_W210
#define XH430_W210
Definition: dynamixel_item.h:63
info_PRO
static const ModelInfo info_PRO
Definition: dynamixel_item.cpp:1056
PRO_PLUS_H54P_200_S500_R
#define PRO_PLUS_H54P_200_S500_R
Definition: dynamixel_item.h:104
info_EXTMX
static const ModelInfo info_EXTMX
Definition: dynamixel_item.cpp:421
items_EXTPRO_A
static const ControlItem items_EXTPRO_A[]
Definition: dynamixel_item.cpp:1128
s_Bus_Watchdog
static const char s_Bus_Watchdog[]
Definition: dynamixel_item.cpp:30
PRO_L42_10_S300_R
#define PRO_L42_10_S300_R
Definition: dynamixel_item.h:76
info_XL320
static const ModelInfo info_XL320
Definition: dynamixel_item.cpp:533
s_Moving_Threshold
static const char s_Moving_Threshold[]
Definition: dynamixel_item.cpp:77
s_Torque_Limit
static const char s_Torque_Limit[]
Definition: dynamixel_item.cpp:113
PRO_L54_30_S500_R
#define PRO_L54_30_S500_R
Definition: dynamixel_item.h:78
s_Present_Position
static const char s_Present_Position[]
Definition: dynamixel_item.cpp:89
s_Max_Torque
static const char s_Max_Torque[]
Definition: dynamixel_item.cpp:69
s_Goal_Torque
static const char s_Goal_Torque[]
Definition: dynamixel_item.cpp:57
RX_24F
#define RX_24F
Definition: dynamixel_item.h:30
RX_28
#define RX_28
Definition: dynamixel_item.h:31
MX_28_2
#define MX_28_2
Definition: dynamixel_item.h:38
s_External_Port_Mode_1
static const char s_External_Port_Mode_1[]
Definition: dynamixel_item.cpp:42
s_External_Port_Data_1
static const char s_External_Port_Data_1[]
Definition: dynamixel_item.cpp:46
s_Moving_Status
static const char s_Moving_Status[]
Definition: dynamixel_item.cpp:76
s_LED_RED
static const char s_LED_RED[]
Definition: dynamixel_item.cpp:66
s_Present_Input_Voltage
static const char s_Present_Input_Voltage[]
Definition: dynamixel_item.cpp:87
s_Punch
static const char s_Punch[]
Definition: dynamixel_item.cpp:98
s_Present_Temperature
static const char s_Present_Temperature[]
Definition: dynamixel_item.cpp:92
COUNT_EX_ITEMS
#define COUNT_EX_ITEMS
Definition: dynamixel_item.cpp:254
s_External_Port_Mode_3
static const char s_External_Port_Mode_3[]
Definition: dynamixel_item.cpp:44
s_Shutdown
static const char s_Shutdown[]
Definition: dynamixel_item.cpp:108
COUNT_Gripper_ITEMS
#define COUNT_Gripper_ITEMS
Definition: dynamixel_item.cpp:1310
s_PWM_Slope
static const char s_PWM_Slope[]
Definition: dynamixel_item.cpp:100
s_Hardware_Error_Status
static const char s_Hardware_Error_Status[]
Definition: dynamixel_item.cpp:59
items_PRO_PLUS
static const ControlItem items_PRO_PLUS[]
Definition: dynamixel_item.cpp:1187
COUNT_EXTXM_ITEMS
#define COUNT_EXTXM_ITEMS
Definition: dynamixel_item.cpp:798
MX_106
#define MX_106
Definition: dynamixel_item.h:41
ControlItem
Definition: dynamixel_item.h:113
COUNT_XL_ITEMS
#define COUNT_XL_ITEMS
Definition: dynamixel_item.cpp:660
s_LED_BLUE
static const char s_LED_BLUE[]
Definition: dynamixel_item.cpp:64
s_LED_GREEN
static const char s_LED_GREEN[]
Definition: dynamixel_item.cpp:65
info_MX
static const ModelInfo info_MX
Definition: dynamixel_item.cpp:305
info_EX
static const ModelInfo info_EX
Definition: dynamixel_item.cpp:256
COUNT_PRO_ITEMS
#define COUNT_PRO_ITEMS
Definition: dynamixel_item.cpp:1054
items_RX
static const ControlItem items_RX[]
Definition: dynamixel_item.cpp:170
COUNT_EXTMX_ITEMS
#define COUNT_EXTMX_ITEMS
Definition: dynamixel_item.cpp:419
s_LED
static const char s_LED[]
Definition: dynamixel_item.cpp:63
COUNT_EXTPRO_A_ITEMS
#define COUNT_EXTPRO_A_ITEMS
Definition: dynamixel_item.cpp:1176
s_P_gain
static const char s_P_gain[]
Definition: dynamixel_item.cpp:80
COUNT_EXTXH_ITEMS
#define COUNT_EXTXH_ITEMS
Definition: dynamixel_item.cpp:930
s_Drive_Mode
static const char s_Drive_Mode[]
Definition: dynamixel_item.cpp:41
COUNT_RX_ITEMS
#define COUNT_RX_ITEMS
Definition: dynamixel_item.cpp:205
s_Position_I_Gain
static const char s_Position_I_Gain[]
Definition: dynamixel_item.cpp:82
s_Present_PWM
static const char s_Present_PWM[]
Definition: dynamixel_item.cpp:90
EX_106
#define EX_106
Definition: dynamixel_item.h:34
items_AX
static const ControlItem items_AX[]
Definition: dynamixel_item.cpp:124
s_Present_Velocity
static const char s_Present_Velocity[]
Definition: dynamixel_item.cpp:93
s_Min_Voltage_Limit
static const char s_Min_Voltage_Limit[]
Definition: dynamixel_item.cpp:72
XW540_T140
#define XW540_T140
Definition: dynamixel_item.h:74
s_Velocity_I_Gain
static const char s_Velocity_I_Gain[]
Definition: dynamixel_item.cpp:114
s_Goal_Position
static const char s_Goal_Position[]
Definition: dynamixel_item.cpp:55
PRO_L54_50_S290_R
#define PRO_L54_50_S290_R
Definition: dynamixel_item.h:79
XH430_V350
#define XH430_V350
Definition: dynamixel_item.h:66
PRO_PLUS_M42P_010_S260_R
#define PRO_PLUS_M42P_010_S260_R
Definition: dynamixel_item.h:98
items_EXTGripper
static const ControlItem items_EXTGripper[]
Definition: dynamixel_item.cpp:1322
COUNT_EXTGripper_ITEMS
#define COUNT_EXTGripper_ITEMS
Definition: dynamixel_item.cpp:1384
XM540_W270
#define XM540_W270
Definition: dynamixel_item.h:61
s_Model_Number
static const char s_Model_Number[]
Definition: dynamixel_item.cpp:73
s_Position_P_Gain
static const char s_Position_P_Gain[]
Definition: dynamixel_item.cpp:83
MX_64_2
#define MX_64_2
Definition: dynamixel_item.h:40
items_XH
static const ControlItem items_XH[]
Definition: dynamixel_item.cpp:810
info_EXTXM
static const ModelInfo info_EXTXM
Definition: dynamixel_item.cpp:800
MX_64
#define MX_64
Definition: dynamixel_item.h:39
XH540_W270
#define XH540_W270
Definition: dynamixel_item.h:69
s_Temperature_Limit
static const char s_Temperature_Limit[]
Definition: dynamixel_item.cpp:110
COUNT_XL320_ITEMS
#define COUNT_XL320_ITEMS
Definition: dynamixel_item.cpp:531
COUNT_XL330_ITEMS
#define COUNT_XL330_ITEMS
Definition: dynamixel_item.cpp:596
s_CCW_Angle_Limit
static const char s_CCW_Angle_Limit[]
Definition: dynamixel_item.cpp:31
AX_12A
#define AX_12A
Definition: dynamixel_item.h:25
PRO_M54_40_S250_R
#define PRO_M54_40_S250_R
Definition: dynamixel_item.h:83
COUNT_MX_ITEMS
#define COUNT_MX_ITEMS
Definition: dynamixel_item.cpp:303


dynamixel_workbench_toolbox
Author(s): Darby Lim , Ryan Shim
autogenerated on Wed Mar 2 2022 00:13:18