Skip to content

Commit fdd35ed

Browse files
authored
Merge pull request commaai#164 from crwusiz/HKG_community
fix
2 parents 972cf73 + f7840e6 commit fdd35ed

File tree

2 files changed

+38
-40
lines changed

2 files changed

+38
-40
lines changed

selfdrive/car/hyundai/interface.py

+36-38
Original file line numberDiff line numberDiff line change
@@ -41,124 +41,124 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False,
4141

4242
# genesis
4343
if candidate == CAR.GENESIS:
44-
ret.lateralTuning.pid.kf = 0.00005
4544
ret.mass = 2060. + STD_CARGO_KG
4645
ret.wheelbase = 3.01
4746
ret.steerRatio = 16.5
47+
ret.lateralTuning.pid.kf = 0.00005
4848
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
4949
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]]
50-
ret.minSteerSpeed = 60 * CV.KPH_TO_MS
5150
elif candidate == CAR.GENESIS_G70:
52-
ret.lateralTuning.pid.kf = 0.00005
5351
ret.mass = 1640. + STD_CARGO_KG
5452
ret.wheelbase = 2.84
55-
ret.steerRatio = 16.5
53+
ret.steerRatio = 16.5
54+
ret.lateralTuning.pid.kf = 0.00005
5655
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
5756
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]]
5857
elif candidate == CAR.GENESIS_G80:
59-
ret.lateralTuning.pid.kf = 0.00005
6058
ret.mass = 2060. + STD_CARGO_KG
6159
ret.wheelbase = 3.01
6260
ret.steerRatio = 16.5
61+
ret.lateralTuning.pid.kf = 0.00005
6362
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
6463
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]]
6564
elif candidate == CAR.GENESIS_G90:
6665
ret.mass = 2200
6766
ret.wheelbase = 3.15
6867
ret.steerRatio = 12.069
68+
ret.lateralTuning.pid.kf = 0.00005
6969
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
7070
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.01]]
7171
# hyundai
7272
elif candidate in [CAR.SANTA_FE]:
73-
ret.lateralTuning.pid.kf = 0.00005
7473
ret.mass = 1694 + STD_CARGO_KG
7574
ret.wheelbase = 2.766
7675
ret.steerRatio = 13.8 * 1.15 # 13.8 is spec end-to-end
76+
ret.lateralTuning.pid.kf = 0.00005
7777
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
7878
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
79-
elif candidate in [CAR.SONATA, CAR.SONATA_HEV]:
80-
ret.lateralTuning.pid.kf = 0.00005
79+
elif candidate in [CAR.SONATA, CAR.SONATA_HEV]:
8180
ret.mass = 1513. + STD_CARGO_KG
8281
ret.wheelbase = 2.84
8382
ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable
8483
tire_stiffness_factor = 0.65
84+
ret.lateralTuning.pid.kf = 0.00005
8585
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
8686
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
87-
elif candidate in [CAR.SONATA19, CAR.SONATA19_HEV]:
88-
ret.lateralTuning.pid.kf = 0.00005
87+
elif candidate in [CAR.SONATA19, CAR.SONATA19_HEV]:
8988
ret.mass = 4497. * CV.LB_TO_KG
9089
ret.wheelbase = 2.804
9190
ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable
91+
ret.lateralTuning.pid.kf = 0.00005
9292
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
9393
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
94-
elif candidate == CAR.PALISADE:
95-
ret.lateralTuning.pid.kf = 0.00005
94+
elif candidate == CAR.PALISADE:
9695
ret.mass = 1999. + STD_CARGO_KG
9796
ret.wheelbase = 2.90
9897
ret.steerRatio = 13.75 * 1.15
98+
ret.lateralTuning.pid.kf = 0.00005
9999
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
100100
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
101-
elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]:
102-
ret.lateralTuning.pid.kf = 0.00006
101+
elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]:
103102
ret.mass = 1275. + STD_CARGO_KG
104103
ret.wheelbase = 2.7
105104
ret.steerRatio = 15.4 # 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535
106105
tire_stiffness_factor = 0.385 # stiffnessFactor settled on 1.0081302973865127
106+
ret.lateralTuning.pid.kf = 0.00006
107107
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
108108
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
109-
elif candidate == CAR.KONA:
110-
ret.lateralTuning.pid.kf = 0.00005
109+
elif candidate == CAR.KONA:
111110
ret.mass = 1275. + STD_CARGO_KG
112111
ret.wheelbase = 2.7
113112
ret.steerRatio = 13.73 * 1.15 # Spec
114113
tire_stiffness_factor = 0.385
114+
ret.lateralTuning.pid.kf = 0.00005
115115
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
116116
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
117-
elif candidate in [CAR.KONA_HEV, CAR.KONA_EV]:
118-
ret.lateralTuning.pid.kf = 0.00006
117+
elif candidate in [CAR.KONA_HEV, CAR.KONA_EV]:
119118
ret.mass = 1685. + STD_CARGO_KG
120119
ret.wheelbase = 2.7
121120
ret.steerRatio = 13.73
122121
tire_stiffness_factor = 0.385
122+
ret.lateralTuning.pid.kf = 0.00006
123123
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
124124
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
125-
elif candidate in [CAR.IONIQ_EV, CAR.IONIQ_HEV]:
126-
ret.lateralTuning.pid.kf = 0.00006
125+
elif candidate in [CAR.IONIQ_EV, CAR.IONIQ_HEV]:
127126
ret.mass = 1490. + STD_CARGO_KG #weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx
128127
ret.wheelbase = 2.7
129128
ret.steerRatio = 13.73 #Spec
130129
tire_stiffness_factor = 0.385
130+
ret.lateralTuning.pid.kf = 0.00006
131131
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
132132
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
133-
elif candidate in [CAR.GRANDEUR, CAR.GRANDEUR_HEV]:
134-
ret.lateralTuning.pid.kf = 0.00005
133+
elif candidate in [CAR.GRANDEUR, CAR.GRANDEUR_HEV]:
135134
ret.mass = 1719. + STD_CARGO_KG
136135
ret.wheelbase = 2.8
137136
ret.steerRatio = 12.5
137+
ret.lateralTuning.pid.kf = 0.00005
138138
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
139139
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
140-
elif candidate == CAR.VELOSTER:
141-
ret.lateralTuning.pid.kf = 0.00005
140+
elif candidate == CAR.VELOSTER:
142141
ret.mass = 3558. * CV.LB_TO_KG
143142
ret.wheelbase = 2.80
144143
ret.steerRatio = 13.75 * 1.15
145144
tire_stiffness_factor = 0.5
145+
ret.lateralTuning.pid.kf = 0.00005
146146
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
147147
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
148148
# kia
149-
elif candidate == CAR.SORENTO:
150-
ret.lateralTuning.pid.kf = 0.00005
149+
elif candidate == CAR.SORENTO:
151150
ret.mass = 1985. + STD_CARGO_KG
152151
ret.wheelbase = 2.78
153152
ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable
153+
ret.lateralTuning.pid.kf = 0.00005
154154
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
155155
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
156-
elif candidate in [CAR.OPTIMA, CAR.OPTIMA_HEV]:
157-
ret.lateralTuning.pid.kf = 0.00005
156+
elif candidate in [CAR.OPTIMA, CAR.OPTIMA_HEV]:
158157
ret.mass = 3558. * CV.LB_TO_KG
159158
ret.wheelbase = 2.80
160159
ret.steerRatio = 13.75
161160
tire_stiffness_factor = 0.5
161+
ret.lateralTuning.pid.kf = 0.00005
162162
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
163163
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
164164
elif candidate == CAR.STINGER:
@@ -174,27 +174,27 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False,
174174
ret.mass = 1825.0 + STD_CARGO_KG
175175
ret.wheelbase = 2.906 # https://www.kia.com/us/en/stinger/specs
176176
ret.steerRatio = 13.56 # 10.28 measured by wheel alignment machine/reported steering angle by OP. 2020 GT Limited AWD has a variable steering ratio ultimately ending in 10.28. 13.56 after 1200km in LiveParamaters (Tunder)
177-
elif candidate == CAR.FORTE:
178-
ret.lateralTuning.pid.kf = 0.00005
177+
elif candidate == CAR.FORTE:
179178
ret.mass = 3558. * CV.LB_TO_KG
180179
ret.wheelbase = 2.80
181180
ret.steerRatio = 13.75
182181
tire_stiffness_factor = 0.5
182+
ret.lateralTuning.pid.kf = 0.00005
183183
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
184184
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
185-
elif candidate == CAR.CEED:
186-
ret.lateralTuning.pid.kf = 0.00005
185+
elif candidate == CAR.CEED:
187186
ret.mass = 1350. + STD_CARGO_KG
188187
ret.wheelbase = 2.65
189188
ret.steerRatio = 13.75
190189
tire_stiffness_factor = 0.5
190+
ret.lateralTuning.pid.kf = 0.00005
191191
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
192192
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
193-
elif candidate == CAR.SPORTAGE:
194-
ret.lateralTuning.pid.kf = 0.00005
193+
elif candidate == CAR.SPORTAGE:
195194
ret.mass = 1985. + STD_CARGO_KG
196195
ret.wheelbase = 2.78
197196
ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable
197+
ret.lateralTuning.pid.kf = 0.00005
198198
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
199199
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
200200
elif candidate in [CAR.NIRO_HEV, CAR.NIRO_EV]:
@@ -213,12 +213,11 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False,
213213
ret.mass = 1737. + STD_CARGO_KG
214214
ret.wheelbase = 2.7
215215
tire_stiffness_factor = 0.385
216-
elif candidate in [CAR.CARDENZA, CAR.CARDENZA_HEV]:
217-
ret.lateralTuning.pid.kf = 0.00005
216+
elif candidate in [CAR.CARDENZA, CAR.CARDENZA_HEV]:
218217
ret.mass = 1575. + STD_CARGO_KG
219218
ret.wheelbase = 2.85
220219
ret.steerRatio = 12.5
221-
ret.steerRateCost = 0.4
220+
ret.lateralTuning.pid.kf = 0.00005
222221
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
223222
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
224223

@@ -244,7 +243,6 @@ def get_params(candidate, fingerprint=gen_empty_fingerprint(), has_relay=False,
244243
ret.longitudinalTuning.deadzoneBP = [0., 40]
245244
ret.longitudinalTuning.deadzoneV = [0., 0.02]
246245

247-
248246
# steer, gas, brake limitations VS speed
249247
ret.steerMaxBP = [0.]
250248
ret.steerMaxV = [1.0]

selfdrive/car/hyundai/values.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -208,9 +208,9 @@ class Buttons:
208208
}],
209209
CAR.STINGER: [{
210210
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8
211-
},{
211+
},{
212212
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1157: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1437: 8, 1456: 4, 1470: 8
213-
}],
213+
}],
214214
CAR.NIRO_EV: [{
215215
127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8
216216
},{

0 commit comments

Comments
 (0)