diff --git a/cereal/car.capnp b/cereal/car.capnp index 4c3dac838a6dea..d08e74c769480f 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -72,8 +72,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { calibrationProgress @47; lowBattery @48; invalidGiraffeHonda @49; - manualSteeringRequired @50; - manualSteeringRequiredBlinkersOn @51; } } @@ -345,7 +343,8 @@ struct CarParams { steerReactance @51 :Float32; steerInductance @52 :Float32; steerResistance @53 :Float32; - + + # Kp and Ki for the longitudinal control longitudinalKpBP @36 :List(Float32); longitudinalKpV @37 :List(Float32); diff --git a/opendbc/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain.dbc index c9a7ecc9c75ce9..306ba01156432f 100644 --- a/opendbc/gm_global_a_powertrain.dbc +++ b/opendbc/gm_global_a_powertrain.dbc @@ -130,7 +130,7 @@ BO_ 481 ASCMSteeringButton: 7 K124_ASCM SG_ DriveModeButton : 39|1@0+ (1,0) [0|1] "" XXX BO_ 485 PSCMSteeringAngle: 8 K43_PSCM - SG_ SteeringWheelAngle : 15|16@0- (0.0625,-0.5) [-525|525] "deg" NEO + SG_ SteeringWheelAngle : 15|16@0- (0.0625,0.3125) [-525|525] "deg" NEO SG_ SteeringWheelRate : 27|12@0- (0.5,0) [-100|100] "deg/s" NEO BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM diff --git a/selfdrive/c b/selfdrive/c new file mode 100644 index 00000000000000..395140864a433b Binary files /dev/null and b/selfdrive/c differ diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 51a0cc363561ac..a5890f7ce91ea3 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -11,7 +11,7 @@ class CarControllerParams(): def __init__(self, car_fingerprint): if car_fingerprint in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS): - self.STEER_MAX = 400 + self.STEER_MAX = 300 self.STEER_STEP = 2 # how often we update the steer cmd self.STEER_DELTA_UP = 7 # ~0.75s time to peak torque (255/50hz/0.75s) self.STEER_DELTA_DOWN = 17 # ~0.3s from peak torque to zero diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index abae74f89af107..8fe1d5beafe27a 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -200,9 +200,9 @@ def get_params(candidate, fingerprint): ret.longPidDeadzoneBP = [0.] ret.longPidDeadzoneV = [0.] - ret.longitudinalKpBP = [0., 5., 35.] - ret.longitudinalKpV = [3.5, 1.1, 0.7] - ret.longitudinalKiBP = [0., 5., 35.] + ret.longitudinalKpBP = [0., 2., 35.] + ret.longitudinalKpV = [3., 1.1, 0.7] + ret.longitudinalKiBP = [0., 2., 35.] ret.longitudinalKiV = [0.25, 0.12, 0.08] ret.steerLimitAlert = True diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 2fca4481dcae98..7997712ec56adc 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -232,7 +232,7 @@ def get_params(candidate, fingerprint): tire_stiffness_factor = 0.8467 ret.steerReactance = 1.0 ret.steerInductance = 1.0 - ret.steerResistance = 0.5 + ret.steerResistance = 1.0 ret.eonToFront = 1.0 ret.steerKpV, ret.steerKiV = [[0.64], [0.192]] ret.steerKf = 0.000064 @@ -317,8 +317,8 @@ def get_params(candidate, fingerprint): ret.wheelbase = 2.81 ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 16.0 # as spec - tire_stiffness_factor = 0.82 - ret.steerKpV, ret.steerKiV = [[0.5], [0.22]] + tire_stiffness_factor = 0.444 # not optimized yet + ret.steerKpV, ret.steerKiV = [[0.38], [0.11]] ret.longitudinalKpBP = [0., 5., 35.] ret.longitudinalKpV = [1.2, 0.8, 0.5] ret.longitudinalKiBP = [0., 35.] @@ -369,18 +369,8 @@ def get_params(candidate, fingerprint): ret.steerMaxBP = [0.] # m/s ret.steerMaxV = [1.] # max steer allowed - # prevent lurching when resuming - if ret.enableGasInterceptor: - ret.gasMaxBP = [0., 8, 35] - ret.gasMaxV = [0.2, 0.6, 0.6] - ret.longitudinalKpBP = [0., 5., 35.] - ret.longitudinalKpV = [1.2, 0.8, 0.5] - else: - ret.gasMaxBP = [0.] # m/s - ret.gasMaxV = [0.] # max gas allowed - - #ret.gasMaxBP = [0.] # m/s - #ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed + ret.gasMaxBP = [0.] # m/s + ret.gasMaxV = [0.6] if ret.enableGasInterceptor else [0.] # max gas allowed ret.brakeMaxBP = [5., 20.] # m/s ret.brakeMaxV = [1., 0.8] # max brake allowed @@ -451,9 +441,6 @@ def update(self, c): ret.cruiseState.available = bool(self.CS.main_on) ret.cruiseState.speedOffset = self.CS.cruise_speed_offset ret.cruiseState.standstill = False - - ret.readdistancelines = self.CS.read_distance_lines - ret.lkMode = self.CS.lkMode # TODO: button presses buttonEvents = [] @@ -528,11 +515,7 @@ def update(self, c): else: self.cam_can_invalid_count = 0 - if not self.CS.lkMode: - events.append(create_event('manualSteeringRequired', [ET.WARNING])) - elif self.CS.lkMode and (self.CS.left_blinker_on or self.CS.right_blinker_on): - events.append(create_event('manualSteeringRequiredBlinkersOn', [ET.WARNING])) - elif self.CS.steer_error: + if self.CS.steer_error: events.append(create_event('steerUnavailable', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE, ET.PERMANENT])) elif self.CS.steer_warning: events.append(create_event('steerTempUnavailable', [ET.WARNING])) @@ -571,10 +554,9 @@ def update(self, c): if self.CP.enableCruise and not ret.cruiseState.enabled and c.actuators.brake <= 0.: # non loud alert if cruise disbales below 25mph as expected (+ a little margin) if ret.vEgo < self.CP.minEnableSpeed + 2.: - # events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE])) - #else: - events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) # send loud alert if slow and cruise disables during braking - + events.append(create_event('speedTooLow', [ET.IMMEDIATE_DISABLE])) + else: + events.append(create_event("cruiseDisabled", [ET.IMMEDIATE_DISABLE])) if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: events.append(create_event('manualRestart', [ET.WARNING])) diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 2020634dacc451..e84e9f3a281682 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -77,6 +77,11 @@ def get_params(candidate, fingerprint): ret.steerActuatorDelay = 0.1 # Default delay tire_stiffness_factor = 1. + ret.steerReactance = 1.0 + ret.steerInductance = 1.0 + ret.steerResistance = 1.0 + ret.eonToFront = 0.5 + if candidate == CAR.SANTA_FE: ret.steerKf = 0.00005 ret.steerRateCost = 0.5 diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 160d9b469b5f8e..97a12da5070145 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -49,6 +49,11 @@ def get_params(candidate, fingerprint): ret.safetyModel = car.CarParams.SafetyModels.noOutput ret.openpilotLongitudinalControl = False + ret.steerReactance = 1.0 + ret.steerInductance = 1.0 + ret.steerResistance = 1.0 + ret.eonToFront = 0.5 + # FIXME: hardcoding honda civic 2016 touring params so they can be used to # scale unknown params for other cars ret.mass = 1700. diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py index 0947317854ccfd..8abd9b517cd4ad 100755 --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -73,6 +73,10 @@ def get_params(candidate, fingerprint): tireStiffnessFront_civic = 192150 tireStiffnessRear_civic = 202500 + ret.steerReactance = 1.0 + ret.steerInductance = 1.0 + ret.steerResistance = 1.0 + ret.eonToFront = 0.5 ret.steerKiBP, ret.steerKpBP = [[0.], [0.]] ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay diff --git a/selfdrive/controls/c b/selfdrive/controls/c new file mode 100644 index 00000000000000..3bc8bdc300b8ef Binary files /dev/null and b/selfdrive/controls/c differ diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index c3db502fcfe4bb..bf48e8826c9000 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -3,9 +3,9 @@ from selfdrive.config import Conversions as CV # kph -V_CRUISE_MAX = 144 -V_CRUISE_MIN = 8 -V_CRUISE_DELTA = 8 +V_CRUISE_MAX = 145 +V_CRUISE_MIN = 10 +V_CRUISE_DELTA = 5 V_CRUISE_ENABLE_MIN = 40 diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index 00b6e018026a84..7225f370657ae2 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -1,5 +1,8 @@ +import zmq import math import numpy as np +import time +import json from selfdrive.controls.lib.pid import PIController from selfdrive.controls.lib.drive_helpers import MPC_COST_LAT from selfdrive.controls.lib.lateral_mpc import libmpc_py @@ -11,17 +14,14 @@ _DT = 0.01 # 100Hz _DT_MPC = 0.05 # 20Hz - def calc_states_after_delay(states, v_ego, steer_angle, curvature_factor, steer_ratio, delay, long_camera_offset): states[0].x = max(0.0, v_ego * delay + long_camera_offset) states[0].psi = v_ego * curvature_factor * math.radians(steer_angle) / steer_ratio * delay return states - def get_steer_max(CP, v_ego): return interp(v_ego, CP.steerMaxBP, CP.steerMaxV) - def apply_deadzone(angle, deadzone): if angle > deadzone: angle -= deadzone @@ -31,37 +31,63 @@ def apply_deadzone(angle, deadzone): angle = 0. return angle - class LatControl(object): def __init__(self, CP): - # Eliminate break-points, since they aren't needed (and would cause problems for resonance) KpV = [np.interp(25.0, CP.steerKpBP, CP.steerKpV) * CP.steerReactance] KiV = [np.interp(25.0, CP.steerKiBP, CP.steerKiV) * CP.steerReactance] Kf = CP.steerKf * CP.steerInductance + print(KpV, KiV, Kf) self.pid = PIController(([0.], KpV), ([0.], KiV), k_f=Kf, pos_limit=1.0) self.last_cloudlog_t = 0.0 self.setup_mpc(CP.steerRateCost) self.smooth_factor = CP.steerInductance * 2.0 * CP.steerActuatorDelay / _DT # Multiplier for inductive component (feed forward) - self.projection_factor = CP.steerReactance * 5.0 * _DT # Mutiplier for reactive component (PI) + self.projection_factor = CP.steerReactance * 5.0 * _DT # Mutiplier for reactive component (PI) self.accel_limit = 2.0 / CP.steerResistance # Desired acceleration limit to prevent "whip steer" (resistive component) self.ff_angle_factor = 0.5 # Kf multiplier for angle-based feed forward self.ff_rate_factor = 5.0 # Kf multiplier for rate-based feed forward self.prev_angle_rate = 0 self.feed_forward = 0.0 + self.steerActuatorDelay = CP.steerActuatorDelay self.last_mpc_ts = 0.0 self.angle_steers_des = 0.0 - self.angle_steers_des_time = 0.0 self.angle_steers_des_mpc = 0.0 + self.angle_steers_des_time = 0.0 + self.avg_angle_steers = 0.0 self.projected_angle_steers = 0.0 + self.left_change = 0.0 + self.right_change = 0.0 + self.path_change = 0.0 + self.prob_adjust = 0.0 self.steer_counter = 1.0 self.steer_counter_prev = 0.0 + self.angle_steers = 0.0 + self.angle_steers_rate = 0.0 self.rough_steers_rate = 0.0 + self.rough_steers_rate_increment = 0.0 self.prev_angle_steers = 0.0 self.calculate_rate = True + # variables for dashboarding + self.context = zmq.Context() + self.steerpub = self.context.socket(zmq.PUB) + self.steerpub.bind("tcp://*:8594") + self.influxString = 'steerData3,testName=none,active=%s,ff_type=%s ff_type_a=%s,ff_type_r=%s,steer_status=%s,' \ + 'steering_control_active=%s,steer_stock_torque=%s,steer_stock_torque_request=%s,mpc_age2=%s,mpc_age=%s,lchange=%s,pchange=%s,rchange=%s,d0=%s,d1=%s,d2=%s,' \ + 'd3=%s,d4=%s,d5=%s,d6=%s,d7=%s,d8=%s,d9=%s,d10=%s,d11=%s,d12=%s,d13=%s,d14=%s,d15=%s,d16=%s,d17=%s,d18=%s,d19=%s,d20=%s,' \ + 'accel_limit=%s,restricted_steer_rate=%s,driver_torque=%s,angle_rate_desired=%s,future_angle_steers=%s,' \ + 'angle_rate=%s,angle_steers=%s,angle_steers_des=%s,self.angle_steers_des_mpc=%s,projected_angle_steers_des=%s,steerRatio=%s,l_prob=%s,' \ + 'r_prob=%s,c_prob=%s,p_prob=%s,l_poly[0]=%s,l_poly[1]=%s,l_poly[2]=%s,l_poly[3]=%s,r_poly[0]=%s,r_poly[1]=%s,r_poly[2]=%s,r_poly[3]=%s,' \ + 'p_poly[0]=%s,p_poly[1]=%s,p_poly[2]=%s,p_poly[3]=%s,c_poly[0]=%s,c_poly[1]=%s,c_poly[2]=%s,c_poly[3]=%s,d_poly[0]=%s,d_poly[1]=%s,' \ + 'd_poly[2]=%s,lane_width=%s,lane_width_estimate=%s,lane_width_certainty=%s,v_ego=%s,p=%s,i=%s,f=%s %s\n~' + + self.steerdata = self.influxString + self.frames = 0 + self.curvature_factor = 0.0 + self.mpc_frame = 0 + def update_rt_params(self, CP): # TODO: Is this really necessary, or is the original reference preserved through the cap n' proto setup? # Real-time tuning: Update these values from the CP if called from real-time tuning logic in controlsd @@ -71,7 +97,7 @@ def update_rt_params(self, CP): self.setup_mpc(CP.steerRateCost) self.smooth_factor = CP.steerInductance * 2.0 * CP.steerActuatorDelay / _DT self.projection_factor = CP.steerReactance * 5.0 * _DT - self.accel_limit = 2.0 / CP.steerResistance + self.accel_limit = 2.0 / CP.steerResistance def setup_mpc(self, steer_rate_cost): self.libmpc = libmpc_py.libmpc @@ -99,45 +125,44 @@ def update(self, active, v_ego, angle_steers, angle_rate, steer_override, d_poly self.steer_counter_prev = self.steer_counter self.rough_steers_rate = (self.rough_steers_rate + 100.0 * (angle_steers - self.prev_angle_steers) / self.steer_counter_prev) / 2.0 self.steer_counter = 0.0 - elif self.steer_counter >= self.steer_counter_prev: - self.rough_steers_rate = (self.steer_counter * self.rough_steers_rate) / (self.steer_counter + 1.0) self.steer_counter += 1.0 - angle_rate = self.rough_steers_rate - # Don't use accelerated rate unless it's from CAN + if self.steer_counter > self.steer_counter_prev: + self.rough_steers_rate = (self.steer_counter * self.rough_steers_rate) / (self.steer_counter + 1.0) + + angle_rate = self.rough_steers_rate accelerated_angle_rate = angle_rate + else: - # If non-zero angle_rate is provided, use it instead - self.calculate_rate = False - # Use steering rate from the last 2 samples to estimate acceleration for a likely future steering rate + # Use steering rate from the last 2 samples to estimate acceleration for a more realistic future steering rate accelerated_angle_rate = 2.0 * angle_rate - self.prev_angle_rate + self.calculate_rate = False # TODO: this creates issues in replay when rewinding time: mpc won't run if self.last_mpc_ts < PL.last_md_ts: self.last_mpc_ts = PL.last_md_ts cur_time = sec_since_boot() mpc_time = float(self.last_mpc_ts / 1000000000.0) - curvature_factor = VM.curvature_factor(v_ego) + self.curvature_factor = VM.curvature_factor(v_ego) - # Determine future angle steers using steer rate - projected_angle_steers = float(angle_steers) + CP.steerActuatorDelay * float(accelerated_angle_rate) + # Determine future angle steers using accelerated steer rate + self.projected_angle_steers = float(angle_steers) + CP.steerActuatorDelay * float(accelerated_angle_rate) - # Determine a proper delay time that includes the model's variable processing time + # Determine a proper delay time that includes the model's processing time, which is variable plan_age = _DT_MPC + cur_time - mpc_time total_delay = CP.steerActuatorDelay + plan_age - l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly)) - r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly)) - p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly)) + self.l_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.l_poly)) + self.r_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.r_poly)) + self.p_poly = libmpc_py.ffi.new("double[4]", list(PL.PP.p_poly)) # account for actuation delay and the age of the plan - self.cur_state = calc_states_after_delay(self.cur_state, v_ego, projected_angle_steers, curvature_factor, - CP.steerRatio, total_delay, CP.eonToFront) + self.cur_state = calc_states_after_delay(self.cur_state, v_ego, self.projected_angle_steers, self.curvature_factor, CP.steerRatio, total_delay, CP.eonToFront) v_ego_mpc = max(v_ego, 5.0) # avoid mpc roughness due to low speed self.libmpc.run_mpc(self.cur_state, self.mpc_solution, - l_poly, r_poly, p_poly, - PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, curvature_factor, v_ego_mpc, PL.PP.lane_width) + self.l_poly, self.r_poly, self.p_poly, + PL.PP.l_prob, PL.PP.r_prob, PL.PP.p_prob, self.curvature_factor, v_ego_mpc, PL.PP.lane_width) self.mpc_updated = True @@ -153,6 +178,7 @@ def update(self, active, v_ego, angle_steers, angle_rate, steer_override, d_poly mpc_time + _DT_MPC + _DT_MPC] self.angle_steers_des_mpc = self.mpc_angles[1] + else: self.libmpc.init(MPC_COST_LAT.PATH, MPC_COST_LAT.LANE, MPC_COST_LAT.HEADING, CP.steerRateCost) self.cur_state[0].delta = math.radians(angle_steers) / CP.steerRatio @@ -161,60 +187,98 @@ def update(self, active, v_ego, angle_steers, angle_rate, steer_override, d_poly self.last_cloudlog_t = cur_time cloudlog.warning("Lateral mpc - nan: True") - cur_time = sec_since_boot() - self.angle_steers_des_time = cur_time + elif self.frames > 0: + self.steerpub.send(self.steerdata) + self.frames = 0 + self.steerdata = self.influxString if v_ego < 0.3 or not active: output_steer = 0.0 + self.ateer_vibrate = 0.0 self.feed_forward = 0.0 self.pid.reset() self.angle_steers_des = angle_steers + self.avg_angle_steers = angle_steers self.cur_state[0].delta = math.radians(angle_steers - angle_offset) / CP.steerRatio else: + cur_time = sec_since_boot() + # Interpolate desired angle between MPC updates self.angle_steers_des = np.interp(cur_time, self.mpc_times, self.mpc_angles) self.angle_steers_des_time = cur_time + self.avg_angle_steers = (4.0 * self.avg_angle_steers + angle_steers) / 5.0 self.cur_state[0].delta = math.radians(self.angle_steers_des - angle_offset) / CP.steerRatio # Determine the target steer rate for desired angle, but prevent the acceleration limit from being exceeded # Restricting the steer rate creates the resistive component needed for resonance - restricted_steer_rate = np.clip(self.angle_steers_des - float(angle_steers) , float(accelerated_angle_rate) - self.accel_limit, - float(accelerated_angle_rate) + self.accel_limit) + restricted_steer_rate = np.clip(self.angle_steers_des - float(angle_steers) , float(accelerated_angle_rate) - self.accel_limit, float(accelerated_angle_rate) + self.accel_limit) # Determine projected desired angle that is within the acceleration limit (prevent the steering wheel from jerking) projected_angle_steers_des = self.angle_steers_des + self.projection_factor * restricted_steer_rate - # Determine future angle steers using accellerated steer rate + # Determine future angle steers using steer rate self.projected_angle_steers = float(angle_steers) + self.projection_factor * float(accelerated_angle_rate) steers_max = get_steer_max(CP, v_ego) self.pid.pos_limit = steers_max self.pid.neg_limit = -steers_max - deadzone = 0.0 if CP.steerControlType == car.CarParams.SteerControlType.torque: - # Decide which feed forward mode should be used (angle or rate). Use more dominant mode, but only if conditions are met - # Spread feed forward out over a period of time to make it inductive (for resonance) + # Decide which feed forward mode should be used (angle or rate). Use more dominant mode, and only if conditions are met + # Spread feed forward out over a period of time to make it more inductive (for resonance) 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 \ and (abs(float(restricted_steer_rate)) > abs(accelerated_angle_rate) or (float(restricted_steer_rate) < 0) != (accelerated_angle_rate < 0)) \ and (float(restricted_steer_rate) < 0) == (float(self.angle_steers_des) - float(angle_offset) - 0.5 < 0): + ff_type = "r" self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + self.ff_rate_factor * v_ego**2 * float(restricted_steer_rate)) / self.smooth_factor elif abs(self.angle_steers_des - float(angle_offset)) > 0.5: - 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 + ff_type = "a" + 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 else: + ff_type = "r" self.feed_forward = (((self.smooth_factor - 1.) * self.feed_forward) + 0.0) / self.smooth_factor + else: + self.feed_forward = self.angle_steers_des # feedforward desired angle + deadzone = 0.0 - # Use projected desired and actual angles instead of "current" values, in order to make PI more reactive (for resonance) - output_steer = self.pid.update(projected_angle_steers_des, self.projected_angle_steers, check_saturation=(v_ego > 10), - override=steer_override, feedforward=self.feed_forward, speed=v_ego, deadzone=deadzone) + # Use projected desired and actual angles instead of "current" values, in order to make PI more reactive (for resonance) + output_steer = self.pid.update(projected_angle_steers_des, self.projected_angle_steers, check_saturation=(v_ego > 10), override=steer_override, + feedforward=self.feed_forward, speed=v_ego, deadzone=deadzone) + + # Hide angle error if being overriden + if steer_override: + self.projected_angle_steers = self.mpc_angles[1] + self.avg_angle_steers = self.mpc_angles[1] + + # All but the last 3 lines after here are for real-time dashboarding + steering_control_active = 0.0 + driver_torque = 0.0 + steer_status = 0.0 + steer_stock_torque = 0.0 + steer_stock_torque_request = 0.0 + self.angle_rate_desired = 0.0 + self.observed_ratio = 0.0 + capture_all = True + if self.mpc_updated or capture_all: + self.frames += 1 + 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,%f,%f,%f,%f,%f,%f,%d|" % (1, \ + ff_type, 1 if ff_type == "a" else 0, 1 if ff_type == "r" else 0, steer_status, steering_control_active, steer_stock_torque, steer_stock_torque_request, \ + cur_time - float(self.last_mpc_ts / 1000000000.0), cur_time - self.mpc_times[0], self.left_change, self.path_change, self.right_change, self.mpc_solution[0].delta[0], self.mpc_solution[0].delta[1], self.mpc_solution[0].delta[2], self.mpc_solution[0].delta[3], self.mpc_solution[0].delta[4], \ + self.mpc_solution[0].delta[5], self.mpc_solution[0].delta[6], self.mpc_solution[0].delta[7], self.mpc_solution[0].delta[8], self.mpc_solution[0].delta[9], \ + self.mpc_solution[0].delta[10], self.mpc_solution[0].delta[11], self.mpc_solution[0].delta[12], self.mpc_solution[0].delta[13], self.mpc_solution[0].delta[14], \ + self.mpc_solution[0].delta[15], self.mpc_solution[0].delta[16], self.mpc_solution[0].delta[17], self.mpc_solution[0].delta[18], self.mpc_solution[0].delta[19], self.mpc_solution[0].delta[20], \ + self.accel_limit, float(restricted_steer_rate), float(driver_torque), self.angle_rate_desired, self.projected_angle_steers, float(angle_rate), \ + angle_steers, self.angle_steers_des, self.mpc_angles[1], projected_angle_steers_des, self.observed_ratio, PL.PP.l_prob, 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], \ + 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], 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)) self.sat_flag = self.pid.saturated self.prev_angle_rate = angle_rate self.prev_angle_steers = angle_steers - # return MPC angle in the unused output (for ALCA) if CP.steerControlType == car.CarParams.SteerControlType.torque: - return output_steer, self.mpc_angles[1] + return output_steer, float(self.angle_steers_des_mpc) else: - return self.mpc_angles[1], float(self.angle_steers_des) + return float(self.angle_steers_des_mpc), float(self.angle_steers_des) diff --git a/selfdrive/controls/lib/latcontrol_helpers.py b/selfdrive/controls/lib/latcontrol_helpers.py index 90abcebf10bf53..3ee859b6572b09 100644 --- a/selfdrive/controls/lib/latcontrol_helpers.py +++ b/selfdrive/controls/lib/latcontrol_helpers.py @@ -6,7 +6,7 @@ _K_CURV_BP = [0., 0.002] # lane width http://safety.fhwa.dot.gov/geometric/pubs/mitigationstrategies/chapter3/3_lanewidth.cfm -_LANE_WIDTH_V = [3., 3.8] +_LANE_WIDTH_V = [2.5, 3.] # break points of speed _LANE_WIDTH_BP = [0., 31.] diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index c6a664fdf3c8b3..16f6e52ba76335 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -1,7 +1,7 @@ from common.numpy_fast import interp from selfdrive.controls.lib.latcontrol_helpers import model_polyfit, calc_desired_path, compute_path_pinv -CAMERA_OFFSET = 0.06 # m from center car to camera +CAMERA_OFFSET = 0.03 # m from center car to camera class PathPlanner(object): def __init__(self): @@ -35,7 +35,7 @@ def update(self, v_ego, md): self.lane_width_certainty += 0.05 * (lr_prob - self.lane_width_certainty) current_lane_width = abs(l_poly[3] - r_poly[3]) self.lane_width_estimate += 0.005 * (current_lane_width - self.lane_width_estimate) - speed_lane_width = interp(v_ego, [0., 31.], [3., 3.8]) + speed_lane_width = interp(v_ego, [0., 31.], [2.8, 3.]) self.lane_width = self.lane_width_certainty * self.lane_width_estimate + \ (1 - self.lane_width_certainty) * speed_lane_width diff --git a/selfdrive/visiond/visiond b/selfdrive/visiond/visiond old mode 100644 new mode 100755 diff --git a/selfdrive/visiond/visiond.056 b/selfdrive/visiond/visiond-057 similarity index 55% rename from selfdrive/visiond/visiond.056 rename to selfdrive/visiond/visiond-057 index 40259afc55c789..caf5de38ae68a7 100755 Binary files a/selfdrive/visiond/visiond.056 and b/selfdrive/visiond/visiond-057 differ