Skip to content

Commit 08f2477

Browse files
authored
Merge branch 'kegman-devel-pilotFFsteer' into kegman-devel-noFFsteer
2 parents 2ccc171 + 907854c commit 08f2477

File tree

5 files changed

+176
-33
lines changed

5 files changed

+176
-33
lines changed

selfdrive/can/parser.cc

+37-7
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,9 @@ class CANParser {
166166
subscriber = zmq_socket(context, ZMQ_SUB);
167167
zmq_setsockopt(subscriber, ZMQ_SUBSCRIBE, "", 0);
168168

169+
forwarder = zmq_socket(context, ZMQ_PUB);
170+
zmq_bind(forwarder, "tcp://*:8592");
171+
169172
std::string tcp_addr_str;
170173

171174
if (sendcan) {
@@ -244,8 +247,17 @@ class CANParser {
244247
// parse the messages
245248
for (int i = 0; i < msg_count; i++) {
246249
auto cmsg = cans[i];
250+
251+
if (cmsg.getDat().size() > 8) continue; //shouldnt ever happen
252+
uint8_t dat[8] = {0};
253+
memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size());
254+
255+
if (can_forward_period_ns > 0) raw_can_values[cmsg.getSrc()][cmsg.getAddress()] = read_u64_be(dat);
256+
257+
//if (((cmsg.getAddress() == 0xe4 or cmsg.getAddress() == 0x33d) and cmsg.getSrc() == bus) or \
258+
// (cmsg.getSrc() != bus and cmsg.getAddress() != 0x33d and cmsg.getAddress() != 0xe4 and \
259+
// (cmsg.getAddress() < 0x240 or cmsg.getAddress() > 0x24A))) {
247260
if (cmsg.getSrc() != bus) {
248-
// DEBUG("skip %d: wrong bus\n", cmsg.getAddress());
249261
continue;
250262
}
251263
auto state_it = message_states.find(cmsg.getAddress());
@@ -254,27 +266,38 @@ class CANParser {
254266
continue;
255267
}
256268

257-
if (cmsg.getDat().size() > 8) continue; //shouldnt ever happen
258-
uint8_t dat[8] = {0};
259-
memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size());
260-
261269
// Assumes all signals in the message are of the same type (little or big endian)
262270
// TODO: allow signals within the same message to have different endianess
263271
auto& sig = message_states[cmsg.getAddress()].parse_sigs[0];
264272
if (sig.is_little_endian) {
265273
p = read_u64_le(dat);
266274
} else {
267275
p = read_u64_be(dat);
268-
}
276+
}
269277

270278
DEBUG(" proc %X: %llx\n", cmsg.getAddress(), p);
271279

272280
state_it->second.parse(sec, cmsg.getBusTime(), p);
273281
}
274282
}
275283

284+
void ForwardCANData(uint64_t sec) {
285+
if (sec > next_can_forward_ns) {
286+
next_can_forward_ns += can_forward_period_ns;
287+
// next_can_forward_ns starts at 0, so it needs to be reset. Also handle delays.
288+
if (sec > next_can_forward_ns) next_can_forward_ns = sec + can_forward_period_ns;
289+
std::string canOut = "";
290+
for (auto src : raw_can_values) {
291+
for (auto pid : src.second) {
292+
canOut = canOut + std::to_string(src.first) + " " + std::to_string(pid.first) + " " + std::to_string(pid.second) + "|";
293+
}
294+
}
295+
zmq_send(forwarder, canOut.data(), canOut.size(), 0);
296+
}
297+
}
298+
276299
void UpdateValid(uint64_t sec) {
277-
can_valid = true;
300+
can_valid = true;
278301
for (const auto& kv : message_states) {
279302
const auto& state = kv.second;
280303
if (state.check_threshold > 0 && (sec - state.seen) > state.check_threshold) {
@@ -317,6 +340,8 @@ class CANParser {
317340
UpdateCans(sec, cans);
318341
}
319342

343+
if (can_forward_period_ns > 0) ForwardCANData(sec);
344+
320345
UpdateValid(sec);
321346

322347
zmq_msg_close(&msg);
@@ -351,6 +376,11 @@ class CANParser {
351376
void *context = NULL;
352377
void *subscriber = NULL;
353378

379+
void *forwarder = NULL;
380+
uint64_t can_forward_period_ns = 100000000;
381+
uint64_t next_can_forward_ns = 0;
382+
std::unordered_map<uint32_t, std::unordered_map<uint32_t, uint64_t>> raw_can_values;
383+
354384
const DBC *dbc = NULL;
355385
std::unordered_map<uint32_t, MessageState> message_states;
356386
};

selfdrive/car/honda/carstate.py

+7-2
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@ def get_can_signals(CP):
3636
("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0),
3737
("STEER_ANGLE", "STEERING_SENSORS", 0),
3838
("STEER_ANGLE_RATE", "STEERING_SENSORS", 0),
39+
("STEER_ANGLE_OFFSET", "STEERING_SENSORS", 0),
3940
("STEER_TORQUE_SENSOR", "STEER_STATUS", 0),
4041
("LEFT_BLINKER", "SCM_FEEDBACK", 0),
4142
("RIGHT_BLINKER", "SCM_FEEDBACK", 0),
@@ -242,7 +243,11 @@ def update(self, cp, cp_cam):
242243
self.user_gas_pressed = self.user_gas > 0 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change
243244

244245
self.gear = 0 if self.CP.carFingerprint == CAR.CIVIC else cp.vl["GEARBOX"]['GEAR']
245-
self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE']
246+
if self.CP.carFingerprint in HONDA_BOSCH:
247+
self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE'] + cp.vl["STEERING_SENSORS"]['STEER_ANGLE_OFFSET']
248+
else:
249+
self.angle_steers = cp.vl["STEERING_SENSORS"]['STEER_ANGLE']
250+
246251
self.angle_steers_rate = cp.vl["STEERING_SENSORS"]['STEER_ANGLE_RATE']
247252

248253
#self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING']
@@ -311,7 +316,7 @@ def update(self, cp, cp_cam):
311316
if self.CP.carFingerprint in (CAR.PILOT, CAR.PILOT_2019):
312317
if self.user_brake > 0.05:
313318
self.brake_pressed = 1
314-
319+
315320
# when user presses distance button on steering wheel
316321
if self.cruise_setting == 3:
317322
if cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] == 0:

selfdrive/car/honda/interface.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -196,7 +196,7 @@ def get_params(candidate, fingerprint):
196196
tire_stiffness_factor = 1.
197197
# Civic at comma has modified steering FW, so different tuning for the Neo in that car
198198
is_fw_modified = os.getenv("DONGLE_ID") in ['99c94dc769b5d96e']
199-
ret.steerKpV, ret.steerKiV = [[0.33], [0.10]] if is_fw_modified else [[0.8], [0.24]]
199+
ret.steerKpV, ret.steerKiV = [[0.264], [0.10]] if is_fw_modified else [[0.45], [0.24]]
200200
if is_fw_modified:
201201
ret.steerKf = 0.00003
202202
ret.longitudinalKpBP = [0., 5., 35.]
@@ -211,7 +211,7 @@ def get_params(candidate, fingerprint):
211211
ret.centerToFront = centerToFront_civic
212212
ret.steerRatio = 14.63 # 10.93 is spec end-to-end
213213
tire_stiffness_factor = 1.
214-
ret.steerKpV, ret.steerKiV = [[0.8], [0.24]]
214+
ret.steerKpV, ret.steerKiV = [[0.45], [0.24]]
215215
ret.longitudinalKpBP = [0., 5., 35.]
216216
ret.longitudinalKpV = [1.2, 0.8, 0.5]
217217
ret.longitudinalKiBP = [0., 35.]
@@ -310,6 +310,7 @@ def get_params(candidate, fingerprint):
310310
ret.steerRatio = 16.0 # as spec
311311
tire_stiffness_factor = 0.82
312312
ret.steerKpV, ret.steerKiV = [[0.5], [0.22]]
313+
ret.steerKf = 0.000078
313314
ret.longitudinalKpBP = [0., 5., 35.]
314315
ret.longitudinalKpV = [1.2, 0.8, 0.5]
315316
ret.longitudinalKiBP = [0., 35.]
@@ -383,7 +384,7 @@ def get_params(candidate, fingerprint):
383384
ret.startAccel = 0.5
384385

385386
ret.steerActuatorDelay = 0.1
386-
ret.steerRateCost = 0.5
387+
ret.steerRateCost = 0.35
387388

388389
return ret
389390

selfdrive/controls/controlsd.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -274,7 +274,7 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last,
274274
v_cruise_kph, plan.vTarget, plan.vTargetFuture, plan.aTarget,
275275
CP, PL.lead_1)
276276
# Steering PID loop and lateral MPC
277-
actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle,
277+
actuators.steer, actuators.steerAngle = LaC.update(active, CS.vEgo, CS.steeringAngle, CS.steeringRate,
278278
CS.steeringPressed, plan.dPoly, angle_offset, CP, VM, PL)
279279

280280
# Send a "steering required alert" if saturation count has reached the limit

selfdrive/controls/lib/latcontrol.py

+127-20
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,8 @@
1+
import zmq
12
import math
23
import numpy as np
4+
import time
5+
import json
36
from selfdrive.controls.lib.pid import PIController
47
from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT
58
from selfdrive.controls.lib.lateral_mpc import libmpc_py
@@ -21,6 +24,14 @@ def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_
2124
def get_steer_max(CP, v_ego):
2225
return interp(v_ego, CP.steerMaxBP, CP.steerMaxV)
2326

27+
def apply_deadzone(angle, deadzone):
28+
if angle > deadzone:
29+
angle -= deadzone
30+
elif angle < -deadzone:
31+
angle += deadzone
32+
else:
33+
angle = 0.
34+
return angle
2435

2536
class LatControl(object):
2637
def __init__(self, CP):
@@ -29,6 +40,25 @@ def __init__(self, CP):
2940
k_f=CP.steerKf, pos_limit=1.0)
3041
self.last_cloudlog_t = 0.0
3142
self.setup_mpc(CP.steerRateCost)
43+
self.smooth_factor = 2.0 * CP.steerActuatorDelay / _DT # Multiplier for inductive component (feed forward)
44+
self.projection_factor = 5.0 * _DT # Mutiplier for reactive component (PI)
45+
self.accel_limit = 5.0 # Desired acceleration limit to prevent "whip steer" (resistive component)
46+
self.ff_angle_factor = 0.5 # Kf multiplier for angle-based feed forward
47+
self.ff_rate_factor = 5.0 # Kf multiplier for rate-based feed forward
48+
self.ratioDelayExp = 2.0 # Exponential coefficient for variable steering rate (delay)
49+
self.ratioDelayScale = 0.0 # Multiplier for variable steering rate (delay)
50+
self.prev_angle_rate = 0
51+
self.feed_forward = 0.0
52+
self.angle_rate_desired = 0.0
53+
54+
# variables for dashboarding
55+
self.context = zmq.Context()
56+
self.steerpub = self.context.socket(zmq.PUB)
57+
self.steerpub.bind("tcp://*:8594")
58+
self.steerdata = ""
59+
self.frames = 0
60+
self.curvature_factor = 0.0
61+
self.slip_factor = 0.0
3262

3363
def setup_mpc(self, steer_rate_cost):
3464
self.libmpc = libmpc_py.libmpc
@@ -52,38 +82,58 @@ def setup_mpc(self, steer_rate_cost):
5282
def reset(self):
5383
self.pid.reset()
5484

55-
def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offset, CP, VM, PL):
56-
cur_time = sec_since_boot()
85+
def update(self, active, v_ego, angle_steers, angle_rate, steer_override, d_poly, angle_offset, CP, VM, PL):
86+
cur_time = sec_since_boot()
5787
self.mpc_updated = False
5888
# TODO: this creates issues in replay when rewinding time: mpc won't run
5989
if self.last_mpc_ts < PL.last_md_ts:
6090
self.last_mpc_ts = PL.last_md_ts
6191
self.angle_steers_des_prev = self.angle_steers_des_mpc
6292

63-
curvature_factor = VM.curvature_factor(v_ego)
93+
self.curvature_factor = VM.curvature_factor(v_ego)
6494

65-
l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly))
66-
r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly))
67-
p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly))
95+
# This is currently disabled, but it is used to compensate for variable steering rate
96+
ratioDelayFactor = 1. + self.ratioDelayScale * abs(angle_steers / 100.) ** self.ratioDelayExp
6897

69-
# account for actuation delay
70-
self.cur_state = calc_states_after_delay(self.cur_state, v_ego, angle_steers, curvature_factor, CP.steerRatio, CP.steerActuatorDelay)
98+
# Determine a proper delay time that includes the model's processing time, which is variable
99+
plan_age = _DT_MPC + cur_time - float(PL.last_md_ts / 1000000000.0)
100+
total_delay = ratioDelayFactor * CP.steerActuatorDelay + plan_age
101+
102+
# Use steering rate from the last 2 samples to estimate acceleration for a more realistic future steering rate
103+
accelerated_angle_rate = 2.0 * angle_rate - self.prev_angle_rate
104+
105+
# Project the future steering angle for the actuator delay only (not model delay)
106+
projected_angle_steers = ratioDelayFactor * CP.steerActuatorDelay * accelerated_angle_rate + angle_steers
107+
108+
self.l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly))
109+
self.r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly))
110+
self.p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly))
111+
112+
# account for actuation delay and the age of the plan
113+
self.cur_state = calc_states_after_delay(self.cur_state, v_ego, projected_angle_steers, self.curvature_factor, CP.steerRatio, total_delay)
71114

72115
v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed
73116
self.libmpc.run_mpc(self.cur_state, self.mpc_solution,
74-
l_poly, r_poly, p_poly,
75-
PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, curvature_factor, v_ego_mpc, PL.PP.lane_width)
117+
self.l_poly, self.r_poly, self.p_poly,
118+
PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, self.curvature_factor, v_ego_mpc, PL.PP.lane_width)
76119

77120
# reset to current steer angle if not active or overriding
78121
if active:
122+
self.isActive = 1
79123
delta_desired = self.mpc_solution[0].delta[1]
80124
else:
125+
self.isActive = 0
81126
delta_desired = math.radians(angle_steers - angle_offset) / CP.steerRatio
82127

83128
self.cur_state[0].delta = delta_desired
84129

85130
self.angle_steers_des_mpc = float(math.degrees(delta_desired * CP.steerRatio) + angle_offset)
86-
self.angle_steers_des_time = cur_time
131+
132+
# Use the model's solve time instead of cur_time
133+
self.angle_steers_des_time = float(PL.last_md_ts / 1000000000.0)
134+
135+
# Use last 2 desired angles to determine the model's desired steer rate
136+
self.angle_rate_desired = (self.angle_steers_des_mpc - self.angle_steers_des_prev) / _DT_MPC
87137
self.mpc_updated = True
88138

89139
# Check for infeasable MPC solution
@@ -97,24 +147,81 @@ def update(self, active, v_ego, angle_steers, steer_override, d_poly, angle_offs
97147
self.last_cloudlog_t = t
98148
cloudlog.warning("Lateral mpc - nan: True")
99149

150+
elif self.steerdata != "" and self.frames > 10:
151+
self.steerpub.send(self.steerdata)
152+
self.frames = 0
153+
self.steerdata = ""
154+
100155
if v_ego < 0.3 or not active:
101156
output_steer = 0.0
157+
self.feed_forward = 0.0
102158
self.pid.reset()
103159
else:
104-
# TODO: ideally we should interp, but for tuning reasons we keep the mpc solution
105-
# constant for 0.05s.
106-
#dt = min(cur_time - self.angle_steers_des_time, _DT_MPC + _DT) + _DT # no greater than dt mpc + dt, to prevent too high extraps
107-
#self.angle_steers_des = self.angle_steers_des_prev + (dt / _DT_MPC) * (self.angle_steers_des_mpc - self.angle_steers_des_prev)
108-
self.angle_steers_des = self.angle_steers_des_mpc
160+
# Interpolate desired angle between MPC updates
161+
self.angle_steers_des = self.angle_steers_des_prev + self.angle_rate_desired * (cur_time - self.angle_steers_des_time)
162+
163+
# Determine the target steer rate for desired angle, but prevent the acceleration limit from being exceeded
164+
# Restricting the steer rate creates the resistive component needed for resonance
165+
restricted_steer_rate = np.clip(self.angle_steers_des - float(angle_steers) , float(angle_rate) - self.accel_limit, float(angle_rate) + self.accel_limit)
166+
167+
# Determine projected desired angle that is within the acceleration limit (prevent the steering wheel from jerking)
168+
projected_angle_steers_des = self.angle_steers_des + self.projection_factor * restricted_steer_rate
169+
170+
# Determine project angle steers using current steer rate
171+
projected_angle_steers = float(angle_steers) + self.projection_factor * float(angle_rate)
172+
109173
steers_max = get_steer_max(CP, v_ego)
110174
self.pid.pos_limit = steers_max
111175
self.pid.neg_limit = -steers_max
112-
steer_feedforward = self.angle_steers_des # feedforward desired angle
176+
113177
if CP.steerControlType == car.CarParams.SteerControlType.torque:
114-
steer_feedforward *= v_ego**2 # proportional to realigning tire momentum (~ lateral accel)
178+
# Decide which feed forward mode should be used (angle or rate). Use more dominant mode, and only if conditions are met
179+
# Spread feed forward out over a period of time to make it more inductive (for resonance)
180+
if abs(self.ff_rate_factor * float(restricted_steer_rate)) > abs(self.ff_angle_factor * float(self.angle_steers_des) - float(angle_offset)) - 0.5 \
181+
and (abs(float(restricted_steer_rate)) > abs(angle_rate) or (float(restricted_steer_rate) < 0) != (angle_rate < 0)) \
182+
and (float(restricted_steer_rate) < 0) == (float(self.angle_steers_des) - float(angle_offset) - 0.5 < 0):
183+
ff_type = "r"
184+
self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + self.ff_rate_factor * v_ego**2 * float(restricted_steer_rate)) / self.smooth_factor
185+
elif abs(self.angle_steers_des - float(angle_offset)) > 0.5:
186+
ff_type = "a"
187+
self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + self.ff_angle_factor * v_ego**2 * float(apply_deadzone(float(self.angle_steers_des) - float(angle_offset), 0.5))) / self.smooth_factor
188+
else:
189+
ff_type = "r"
190+
self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + 0.0) / self.smooth_factor
191+
else:
192+
self.feed_forward = self.angle_steers_des_mpc # feedforward desired angle
115193
deadzone = 0.0
116-
output_steer = self.pid.update(self.angle_steers_des, angle_steers, check_saturation=(v_ego > 10), override=steer_override,
117-
feedforward=steer_feedforward, speed=v_ego, deadzone=deadzone)
194+
195+
# Use projected desired and actual angles instead of "current" values, in order to make PI more reactive (for resonance)
196+
output_steer = self.pid.update(projected_angle_steers_des, projected_angle_steers, check_saturation=(v_ego > 10), override=steer_override,
197+
feedforward=self.feed_forward, speed=v_ego, deadzone=deadzone)
198+
199+
200+
# All but the last 3 lines after here are for real-time dashboarding
201+
self.pCost = 0.0
202+
self.lCost = 0.0
203+
self.rCost = 0.0
204+
self.hCost = 0.0
205+
self.srCost = 0.0
206+
self.last_ff_a = 0.0
207+
self.last_ff_r = 0.0
208+
self.center_angle = 0.0
209+
self.steer_zero_crossing = 0.0
210+
self.steer_rate_cost = 0.0
211+
self.avg_angle_rate = 0.0
212+
self.angle_rate_count = 0.0
213+
driver_torque = 0.0
214+
steer_motor = 0.0
215+
self.frames += 1
216+
217+
self.steerdata += ("%d,%s,%d,%d,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%d|" % (self.isActive, \
218+
ff_type, 1 if ff_type == "a" else 0, 1 if ff_type == "r" else 0, self.cur_state[0].x, self.cur_state[0].y, self.cur_state[0].psi, self.cur_state[0].delta, self.cur_state[0].t, self.curvature_factor, self.slip_factor ,self.smooth_factor, self.accel_limit, float(restricted_steer_rate) ,self.ff_angle_factor, self.ff_rate_factor, self.pCost, self.lCost, self.rCost, self.hCost, self.srCost, steer_motor, float(driver_torque), \
219+
self.angle_rate_count, self.angle_rate_desired, self.avg_angle_rate, projected_angle_steers, float(angle_rate), self.steer_zero_crossing, self.center_angle, angle_steers, self.angle_steers_des, angle_offset, \
220+
self.angle_steers_des_mpc, CP.steerRatio, CP.steerKf, CP.steerKpV[0], CP.steerKiV[0], CP.steerRateCost, PL.PP.l_prob, \
221+
PL.PP.r_prob, PL.PP.c_prob, PL.PP.p_prob, self.l_poly[0], self.l_poly[1], self.l_poly[2], self.l_poly[3], self.r_poly[0], self.r_poly[1], self.r_poly[2], self.r_poly[3], \
222+
self.p_poly[0], self.p_poly[1], self.p_poly[2], self.p_poly[3], PL.PP.c_poly[0], PL.PP.c_poly[1], PL.PP.c_poly[2], PL.PP.c_poly[3], PL.PP.d_poly[0], PL.PP.d_poly[1], \
223+
PL.PP.d_poly[2], PL.PP.lane_width, PL.PP.lane_width_estimate, PL.PP.lane_width_certainty, v_ego, self.pid.p, self.pid.i, self.pid.f, int(time.time() * 100) * 10000000))
118224

119225
self.sat_flag = self.pid.saturated
226+
self.prev_angle_rate = angle_rate
120227
return output_steer, float(self.angle_steers_des)

0 commit comments

Comments
 (0)