forked from robotology/robots-configuration
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathicub_right_arm_handOnly.ini
111 lines (66 loc) · 8.49 KB
/
icub_right_arm_handOnly.ini
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
// by MAGGIA
// Initialization file for robot right_arm, 8 dof on can bus controller.
//
[CAN]
CanAddresses 3 4 5 6 7 8
CanDeviceNum 0
NetworkId RIGHTARM
CanMyAddress 0
CanPollingInterval 10
CanTimeout 300
CanTxTimeout 500
CanRxTimeout 500
broadcast_pos 1 1 1 1 1 1 1 1 1 1 1 1
broadcast_pid 0 0 0 0 0 0 0 0 0 0 0 0
broadcast_fault 1 1 1 1 1 1 1 1 1 1 1 1
broadcast_current 0 0 0 0 0 0 0 0 0 0 0 0
broadcast_overflow 1 1 1 1 1 1 1 1 1 1 1 1
broadcast_canprint 1 1 1 1 1 1 1 1 1 1 1 1
broadcast_vel_acc 0 0 0 0 0 0 0 0 0 0 0 0
[analog right_hand] [analog right_arm]
CanAddress 14
Format 8 //MAIS BOARD
Channels 16
Period 10 //ms
[GENERAL]
Joints 12 // the number of joints of the robot part
// 0 1 2 3 4 5 6 7 8 9 10 11
AxisMap 0 1 2 3 4 5 6 7 8 9 10 11
Encoder 706.67 11.375 11.375 34.45 24.89 -2.46 -2.53 -2.46 -2.52 -2.53 -2.32 -2.22
Zeros 90 180 180 14.5 19.29 -94.07 -180.00 -94.07 -183.97 -93.95 -192.92 -310.50
Verbose 0
[VELOCITY]
Shifts 8 8 8 8 8 8 8 8 8 8 8 8
// 0 1 2 3 4 5 6 7 8 9 10 11
[LIMITS]
JntPosMax 90 25 40 60 90 90 180 90 180 90 180 270
jntPosMin -90 -90 -20 0 0 0 0 0 0 0 0 0
// Joint 0 1 2 3 4 5 6 7 8 9 10 11
Currents 360 500 500 500 485 485 485 485 485 485 485 485
// Proportional Derivative Integral Integral Limit PWM Limit scale factor >> offset
[PIDS]
Pid0 200 1000 1 1333 1333 6 0
Pid1 1000 10000 1 1333 633 5 0
Pid2 1000 10000 1 1333 633 8 0
Pid3 200 200 1 1333 633 4 0
Pid4 -8000 -32000 -5 1333 1333 10 0
Pid5 -8000 -32000 -5 1333 1333 10 0
Pid6 8000 32000 5 1333 1333 10 0
Pid7 -8000 -32000 -5 1333 1333 10 0
Pid8 -8000 -32000 -5 1333 1333 10 0
Pid9 -8000 -32000 -5 1333 1333 10 0
Pid10 8000 32000 5 1333 1333 10 0
Pid11 120 1250 0 1333 1333 5 0
[CALIBRATION]
// Joint 0 1 2 3 4 5 6 7 8 9 10 11
CalibrationType 0 3 3 3 3 4 4 4 4 4 4 4
Calibration1 500 2047.5 2047.5 500 511.8 205 10 237 14 228 10 738
Calibration2 -20 10 10 100 10 10 30 10 10 10 10 10
Calibration3 0 466.375 693.875 0 0 6000 6800 6000 -7200 6000 7100 14000
PositionZero 0 0 0 15 30 0 0 0 0 0 0 0
VelocityZero 30 30 30 100 100 100 100 100 100 100 100 100
[HOME]
// Joint 0 1 2 3 4 5 6 7 8 9 10 11
PositionHome 0 0 40 15 30 0 0 0 0 0 0 0
VelocityHome 30 30 30 100 10 10 10 10 10 10 10 10
[ENDINI] // do not remove this line!