File tree Expand file tree Collapse file tree 20 files changed +1477
-2
lines changed Expand file tree Collapse file tree 20 files changed +1477
-2
lines changed Original file line number Diff line number Diff line change 1
1
Number Name
2
+ 30 mx_28.model
2
3
220 omy_hat.model
3
4
230 omy_end.model
4
5
231 omy_end_rh_p12_rn.model
6
+ 311 mx_64.model
7
+ 321 mx_106.model
5
8
350 xl320.model
6
9
536 sensorxel_joy.model
7
10
537 ffw_g40_imu.model
@@ -48,13 +51,27 @@ Number Name
48
51
1270 xw430_t333.model
49
52
1310 xw540_h260.model
50
53
2000 ph42_020_s300.model
54
+ 2010 ph54_100_s500.model
55
+ 2020 ph54_200_s500.model
56
+ 2100 pm42_010_s260.model
57
+ 2110 pm54_040_s250.model
58
+ 2120 pm54_060_s250.model
51
59
4000 ym070_210_m001.model
60
+ 4010 ym070_210_b001.model
52
61
4020 ym070_210_r051.model
53
62
4030 ym070_210_r099.model
63
+ 4040 ym070_210_a051.model
54
64
4050 ym070_210_a099.model
55
65
4120 ym080_230_m001.model
56
66
4130 ym080_230_b001.model
57
67
4140 ym080_230_r051.model
58
68
4150 ym080_230_r099.model
69
+ 4160 ym080_230_a051.model
59
70
4170 ym080_230_a099.model
60
71
35074 rh_p12_rn.model
72
+ 43289 m42_10_s260_ra.model
73
+ 46097 m54_40_s250_ra.model
74
+ 46353 m54_60_s250_ra.model
75
+ 51201 h42_20_s300_ra.model
76
+ 53769 h54_100_s500_ra.model
77
+ 54025 h54_200_s500_ra.model
Original file line number Diff line number Diff line change
1
+ [type info]
2
+ name value
3
+ value_of_zero_radian_position 0
4
+ value_of_max_radian_position 303750
5
+ value_of_min_radian_position -303750
6
+ min_radian -3.14159265
7
+ max_radian 3.14159265
8
+
9
+ [unit info]
10
+ Data Name value unit Sign Type
11
+ Present Velocity 0.0010471976 rad/s signed
12
+ Goal Velocity 0.0010471976 rad/s signed
13
+
14
+ [control table]
15
+ Address Size Data Name
16
+ 0 2 Model Number
17
+ 2 4 Model Information
18
+ 6 1 Firmware Version
19
+ 7 1 ID
20
+ 8 1 Baud Rate
21
+ 9 1 Return Delay Time
22
+ 10 1 Drive Mode
23
+ 11 1 Operating Mode
24
+ 12 1 Secondary ID
25
+ 20 4 Homing Offset
26
+ 24 4 Moving Threshold
27
+ 31 1 Temperature Limit
28
+ 32 2 Max Voltage Limit
29
+ 34 2 Min Voltage Limit
30
+ 36 2 PWM Limit
31
+ 38 2 Current Limit
32
+ 40 4 Acceleration Limit
33
+ 44 4 Velocity Limit
34
+ 48 4 Max Position Limit
35
+ 52 4 Min Position Limit
36
+ 56 1 External Port Mode 1
37
+ 57 1 External Port Mode 2
38
+ 58 1 External Port Mode 3
39
+ 59 1 External Port Mode 4
40
+ 63 1 Shutdown
41
+ 512 1 Torque Enable
42
+ 513 1 LED Red
43
+ 514 1 LED Green
44
+ 515 1 LED Blue
45
+ 516 1 Status Return Level
46
+ 517 1 Registered Instruction
47
+ 518 1 Hardware Error Status
48
+ 524 2 Velocity I Gain
49
+ 526 2 Velocity P Gain
50
+ 528 2 Position D Gain
51
+ 532 2 Position P Gain
52
+ 530 2 Position I Gain
53
+ 536 2 Feedforward 2nd Gain
54
+ 538 2 Feedforward 1st Gain
55
+ 546 1 Bus Watchdog
56
+ 548 2 Goal PWM
57
+ 550 2 Goal Current
58
+ 552 4 Goal Velocity
59
+ 556 4 Profile Acceleration
60
+ 560 4 Profile Velocity
61
+ 564 4 Goal Position
62
+ 568 2 Realtime Tick
63
+ 570 1 Moving
64
+ 571 1 Moving Status
65
+ 572 2 Present PWM
66
+ 574 2 Present Current
67
+ 576 4 Present Velocity
68
+ 580 4 Present Position
69
+ 584 4 Velocity Trajectory
70
+ 588 4 Position Trajectory
71
+ 592 2 Present Input Voltage
72
+ 594 1 Present Temperature
73
+ 168 2 Indirect Address 1
74
+ 634 1 Indirect Data 1
75
+ 168 2 Indirect Address Write
76
+ 634 1 Indirect Data Write
77
+ 296 2 Indirect Address Read
78
+ 698 1 Indirect Data Read
Original file line number Diff line number Diff line change
1
+ [type info]
2
+ name value
3
+ value_of_zero_radian_position 0
4
+ value_of_max_radian_position 501923
5
+ value_of_min_radian_position -501923
6
+ min_radian -3.14159265
7
+ max_radian 3.14159265
8
+
9
+ [unit info]
10
+ Data Name value unit Sign Type
11
+ Present Velocity 0.0010471976 rad/s signed
12
+ Goal Velocity 0.0010471976 rad/s signed
13
+
14
+ [control table]
15
+ Address Size Data Name
16
+ 0 2 Model Number
17
+ 2 4 Model Information
18
+ 6 1 Firmware Version
19
+ 7 1 ID
20
+ 8 1 Baud Rate
21
+ 9 1 Return Delay Time
22
+ 10 1 Drive Mode
23
+ 11 1 Operating Mode
24
+ 12 1 Secondary ID
25
+ 20 4 Homing Offset
26
+ 24 4 Moving Threshold
27
+ 31 1 Temperature Limit
28
+ 32 2 Max Voltage Limit
29
+ 34 2 Min Voltage Limit
30
+ 36 2 PWM Limit
31
+ 38 2 Current Limit
32
+ 40 4 Acceleration Limit
33
+ 44 4 Velocity Limit
34
+ 48 4 Max Position Limit
35
+ 52 4 Min Position Limit
36
+ 56 1 External Port Mode 1
37
+ 57 1 External Port Mode 2
38
+ 58 1 External Port Mode 3
39
+ 59 1 External Port Mode 4
40
+ 63 1 Shutdown
41
+ 512 1 Torque Enable
42
+ 513 1 LED Red
43
+ 514 1 LED Green
44
+ 515 1 LED Blue
45
+ 516 1 Status Return Level
46
+ 517 1 Registered Instruction
47
+ 518 1 Hardware Error Status
48
+ 524 2 Velocity I Gain
49
+ 526 2 Velocity P Gain
50
+ 528 2 Position D Gain
51
+ 532 2 Position P Gain
52
+ 530 2 Position I Gain
53
+ 536 2 Feedforward 2nd Gain
54
+ 538 2 Feedforward 1st Gain
55
+ 546 1 Bus Watchdog
56
+ 548 2 Goal PWM
57
+ 550 2 Goal Current
58
+ 552 4 Goal Velocity
59
+ 556 4 Profile Acceleration
60
+ 560 4 Profile Velocity
61
+ 564 4 Goal Position
62
+ 568 2 Realtime Tick
63
+ 570 1 Moving
64
+ 571 1 Moving Status
65
+ 572 2 Present PWM
66
+ 574 2 Present Current
67
+ 576 4 Present Velocity
68
+ 580 4 Present Position
69
+ 584 4 Velocity Trajectory
70
+ 588 4 Position Trajectory
71
+ 592 2 Present Input Voltage
72
+ 594 1 Present Temperature
73
+ 168 2 Indirect Address 1
74
+ 634 1 Indirect Data 1
75
+ 168 2 Indirect Address Write
76
+ 634 1 Indirect Data Write
77
+ 296 2 Indirect Address Read
78
+ 698 1 Indirect Data Read
Original file line number Diff line number Diff line change
1
+ [type info]
2
+ name value
3
+ value_of_zero_radian_position 0
4
+ value_of_max_radian_position 501923
5
+ value_of_min_radian_position -501923
6
+ min_radian -3.14159265
7
+ max_radian 3.14159265
8
+
9
+ [unit info]
10
+ Data Name value unit Sign Type
11
+ Present Velocity 0.0010471976 rad/s signed
12
+ Goal Velocity 0.0010471976 rad/s signed
13
+
14
+ [control table]
15
+ Address Size Data Name
16
+ 0 2 Model Number
17
+ 2 4 Model Information
18
+ 6 1 Firmware Version
19
+ 7 1 ID
20
+ 8 1 Baud Rate
21
+ 9 1 Return Delay Time
22
+ 10 1 Drive Mode
23
+ 11 1 Operating Mode
24
+ 12 1 Secondary ID
25
+ 20 4 Homing Offset
26
+ 24 4 Moving Threshold
27
+ 31 1 Temperature Limit
28
+ 32 2 Max Voltage Limit
29
+ 34 2 Min Voltage Limit
30
+ 36 2 PWM Limit
31
+ 38 2 Current Limit
32
+ 40 4 Acceleration Limit
33
+ 44 4 Velocity Limit
34
+ 48 4 Max Position Limit
35
+ 52 4 Min Position Limit
36
+ 56 1 External Port Mode 1
37
+ 57 1 External Port Mode 2
38
+ 58 1 External Port Mode 3
39
+ 59 1 External Port Mode 4
40
+ 63 1 Shutdown
41
+ 512 1 Torque Enable
42
+ 513 1 LED Red
43
+ 514 1 LED Green
44
+ 515 1 LED Blue
45
+ 516 1 Status Return Level
46
+ 517 1 Registered Instruction
47
+ 518 1 Hardware Error Status
48
+ 524 2 Velocity I Gain
49
+ 526 2 Velocity P Gain
50
+ 528 2 Position D Gain
51
+ 532 2 Position P Gain
52
+ 530 2 Position I Gain
53
+ 536 2 Feedforward 2nd Gain
54
+ 538 2 Feedforward 1st Gain
55
+ 546 1 Bus Watchdog
56
+ 548 2 Goal PWM
57
+ 550 2 Goal Current
58
+ 552 4 Goal Velocity
59
+ 556 4 Profile Acceleration
60
+ 560 4 Profile Velocity
61
+ 564 4 Goal Position
62
+ 568 2 Realtime Tick
63
+ 570 1 Moving
64
+ 571 1 Moving Status
65
+ 572 2 Present PWM
66
+ 574 2 Present Current
67
+ 576 4 Present Velocity
68
+ 580 4 Present Position
69
+ 584 4 Velocity Trajectory
70
+ 588 4 Position Trajectory
71
+ 592 2 Present Input Voltage
72
+ 594 1 Present Temperature
73
+ 168 2 Indirect Address 1
74
+ 634 1 Indirect Data 1
75
+ 168 2 Indirect Address Write
76
+ 634 1 Indirect Data Write
77
+ 296 2 Indirect Address Read
78
+ 698 1 Indirect Data Read
Original file line number Diff line number Diff line change
1
+ [type info]
2
+ name value
3
+ value_of_zero_radian_position 0
4
+ value_of_max_radian_position 263187
5
+ value_of_min_radian_position -263187
6
+ min_radian -3.14159265
7
+ max_radian 3.14159265
8
+
9
+ [unit info]
10
+ Data Name value unit Sign Type
11
+ Present Velocity 0.0010471976 rad/s signed
12
+ Goal Velocity 0.0010471976 rad/s signed
13
+
14
+ [control table]
15
+ Address Size Data Name
16
+ 0 2 Model Number
17
+ 2 4 Model Information
18
+ 6 1 Firmware Version
19
+ 7 1 ID
20
+ 8 1 Baud Rate
21
+ 9 1 Return Delay Time
22
+ 10 1 Drive Mode
23
+ 11 1 Operating Mode
24
+ 12 1 Secondary ID
25
+ 20 4 Homing Offset
26
+ 24 4 Moving Threshold
27
+ 31 1 Temperature Limit
28
+ 32 2 Max Voltage Limit
29
+ 34 2 Min Voltage Limit
30
+ 36 2 PWM Limit
31
+ 38 2 Current Limit
32
+ 40 4 Acceleration Limit
33
+ 44 4 Velocity Limit
34
+ 48 4 Max Position Limit
35
+ 52 4 Min Position Limit
36
+ 56 1 External Port Mode 1
37
+ 57 1 External Port Mode 2
38
+ 58 1 External Port Mode 3
39
+ 59 1 External Port Mode 4
40
+ 63 1 Shutdown
41
+ 512 1 Torque Enable
42
+ 513 1 LED Red
43
+ 514 1 LED Green
44
+ 515 1 LED Blue
45
+ 516 1 Status Return Level
46
+ 517 1 Registered Instruction
47
+ 518 1 Hardware Error Status
48
+ 524 2 Velocity I Gain
49
+ 526 2 Velocity P Gain
50
+ 528 2 Position D Gain
51
+ 532 2 Position P Gain
52
+ 530 2 Position I Gain
53
+ 536 2 Feedforward 2nd Gain
54
+ 538 2 Feedforward 1st Gain
55
+ 546 1 Bus Watchdog
56
+ 548 2 Goal PWM
57
+ 550 2 Goal Current
58
+ 552 4 Goal Velocity
59
+ 556 4 Profile Acceleration
60
+ 560 4 Profile Velocity
61
+ 564 4 Goal Position
62
+ 568 2 Realtime Tick
63
+ 570 1 Moving
64
+ 571 1 Moving Status
65
+ 572 2 Present PWM
66
+ 574 2 Present Current
67
+ 576 4 Present Velocity
68
+ 580 4 Present Position
69
+ 584 4 Velocity Trajectory
70
+ 588 4 Position Trajectory
71
+ 592 2 Present Input Voltage
72
+ 594 1 Present Temperature
73
+ 168 2 Indirect Address 1
74
+ 634 1 Indirect Data 1
75
+ 168 2 Indirect Address Write
76
+ 634 1 Indirect Data Write
77
+ 296 2 Indirect Address Read
78
+ 698 1 Indirect Data Read
You can’t perform that action at this time.
0 commit comments