class Controls: def __init__(self, sm=None, pm=None, can_sock=None, CI=None): config_realtime_process(4 if TICI else 3, Priority.CTRL_HIGH) # Setup sockets self.pm = pm if self.pm is None: self.pm = messaging.PubMaster([ 'sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams' ]) self.camera_packets = ["roadCameraState", "driverCameraState"] if TICI: self.camera_packets.append("wideRoadCameraState") self.can_sock = can_sock if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 self.can_sock = messaging.sub_sock('can', timeout=can_timeout) if TICI: self.log_sock = messaging.sub_sock('androidLog') if CI is None: # wait for one pandaState and one CAN packet print("Waiting for CAN messages...") get_one_can(self.can_sock) self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan']) else: self.CI, self.CP = CI, CI.CP params = Params() self.joystick_mode = params.get_bool("JoystickDebugMode") or ( self.CP.notCar and sm is None) joystick_packet = ['testJoystick'] if self.joystick_mode else [] self.sm = sm if self.sm is None: ignore = ['driverCameraState', 'managerState' ] if SIMULATION else None self.sm = messaging.SubMaster( [ 'deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', 'managerState', 'liveParameters', 'radarState' ] + self.camera_packets + joystick_packet, ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) # set alternative experiences from parameters self.disengage_on_accelerator = params.get_bool( "DisengageOnAccelerator") self.CP.alternativeExperience = 0 if not self.disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS # read params self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") passive = params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' controller_available = self.CI.CC is not None and not passive and not self.CP.dashcamOnly self.read_only = not car_recognized or not controller_available or self.CP.dashcamOnly if self.read_only: safety_config = car.CarParams.SafetyConfig.new_message() safety_config.safetyModel = car.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] # Write CarParams for radard cp_bytes = self.CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) self.CC = car.CarControl.new_message() self.CS_prev = car.CarState.new_message() self.AM = AlertManager() self.events = Events() self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'indi': self.LaC = LatControlINDI(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'lqr': self.LaC = LatControlLQR(self.CP, self.CI) self.initialized = False self.state = State.disabled self.enabled = False self.active = False self.can_rcv_error = False self.soft_disable_timer = 0 self.v_cruise_kph = 255 self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 self.can_rcv_error_counter = 0 self.last_blinker_frame = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = False self.button_timers = { ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0 } self.last_actuators = car.CarControl.Actuators.new_message() # TODO: no longer necessary, aside from process replay self.sm['liveParameters'].valid = True self.startup_event = get_startup_event(car_recognized, controller_available, len(self.CP.carFw) > 0) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) if len(self.CP.carFw) > 0: set_offroad_alert("Offroad_CarUnrecognized", True) else: set_offroad_alert("Offroad_NoFirmware", True) elif self.read_only: self.events.add(EventName.dashcamMode, static=True) elif self.joystick_mode: self.events.add(EventName.joystickDebug, static=True) self.startup_event = None # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default def update_events(self, CS): """Compute carEvents from carState""" self.events.clear() # Add startup event if self.startup_event is not None: self.events.add(self.startup_event) self.startup_event = None # Don't add any more events if not initialized if not self.initialized: self.events.add(EventName.controlsInitializing) return # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)): self.events.add(EventName.pedalPressed) if CS.gasPressed: self.events.add( EventName.pedalPressedPreEnable if self. disengage_on_accelerator else EventName.gasPressedOverride) self.events.add_from_msg(CS.events) if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) # Create events for battery, temperature, disk space, and memory if EON and (self.sm['peripheralState'].pandaType != PandaType.uno) and \ self.sm['deviceState'].batteryPercent < 1 and self.sm['deviceState'].chargingError: # at zero percent battery, while discharging, OP should not allowed self.events.add(EventName.lowBattery) if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) # TODO: make tici threshold the same if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65) and not SIMULATION: self.events.add(EventName.lowMemory) # TODO: enable this once loggerd CPU usage is more reasonable #cpus = list(self.sm['deviceState'].cpuUsagePercent)[:(-1 if EON else None)] #if max(cpus, default=0) > 95 and not SIMULATION: # self.events.add(EventName.highCpuUsage) # Alert if fan isn't spinning for 5 seconds if self.sm['peripheralState'].pandaType in (PandaType.uno, PandaType.dos): if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm[ 'deviceState'].fanSpeedPercentDesired > 50: if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0: self.events.add(EventName.fanMalfunction) else: self.last_functional_fan_frame = self.sm.frame # Handle calibration status cal_status = self.sm['liveCalibration'].calStatus if cal_status != Calibration.CALIBRATED: if cal_status == Calibration.UNCALIBRATED: self.events.add(EventName.calibrationIncomplete) else: self.events.add(EventName.calibrationInvalid) # Handle lane change if self.sm[ 'lateralPlan'].laneChangeState == LaneChangeState.preLaneChange: direction = self.sm['lateralPlan'].laneChangeDirection if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ (CS.rightBlindspot and direction == LaneChangeDirection.right): self.events.add(EventName.laneChangeBlocked) else: if direction == LaneChangeDirection.left: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) elif self.sm['lateralPlan'].laneChangeState in ( LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing): self.events.add(EventName.laneChange) if not CS.canValid: self.events.add(EventName.canError) for i, pandaState in enumerate(self.sm['pandaStates']): # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput if i < len(self.CP.safetyConfigs): safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ pandaState.alternativeExperience != self.CP.alternativeExperience else: safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES if safety_mismatch or self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if log.PandaState.FaultType.relayMalfunction in pandaState.faults: self.events.add(EventName.relayMalfunction) # Check for HW or system issues if len(self.sm['radarState'].radarErrors): self.events.add(EventName.radarFault) elif not self.sm.valid["pandaStates"]: self.events.add(EventName.usbError) elif not self.sm.all_checks() or self.can_rcv_error: if not self.sm.all_alive(): self.events.add(EventName.commIssue) elif not self.sm.all_freq_ok(): self.events.add(EventName.commIssueAvgFreq) else: # invalid or can_rcv_error. self.events.add(EventName.commIssue) if not self.logged_comm_issue: invalid = [ s for s, valid in self.sm.valid.items() if not valid ] not_alive = [ s for s, alive in self.sm.alive.items() if not alive ] not_freq_ok = [ s for s, freq_ok in self.sm.freq_ok.items() if not freq_ok ] cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive, not_freq_ok=not_freq_ok, can_error=self.can_rcv_error, error=True) self.logged_comm_issue = True else: self.logged_comm_issue = False if not self.sm['liveParameters'].valid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['lateralPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) if not self.sm['liveLocationKalman'].sensorsOK and not NOSENSOR: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) if not self.sm['liveLocationKalman'].deviceStable: self.events.add(EventName.deviceFalling) if not REPLAY: # Check for mismatch between openpilot and car's PCM cruise_mismatch = CS.cruiseState.enabled and ( not self.enabled or not self.CP.pcmCruise) self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 if self.cruise_mismatch_counter > int(3. / DT_CTRL): self.events.add(EventName.cruiseMismatch) # Check for FCW stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 model_fcw = self.sm[ 'modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled if planner_fcw or model_fcw: self.events.add(EventName.fcw) if TICI: for m in messaging.drain_sock(self.log_sock, wait_for_one=False): try: msg = m.androidLog.message if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): csid = msg.split("CSID:")[-1].split(" ")[0] evt = CSID_MAP.get(csid, None) if evt is not None: self.events.add(evt) except UnicodeDecodeError: pass # TODO: fix simulator if not SIMULATION: if not NOSENSOR: if not self.sm['liveLocationKalman'].gpsOK and ( self.distance_traveled > 1000): # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes self.events.add(EventName.noGps) if not self.sm.all_alive(self.camera_packets): self.events.add(EventName.cameraMalfunction) elif not self.sm.all_freq_ok(self.camera_packets): self.events.add(EventName.cameraFrameRate) if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) if self.sm['liveLocationKalman'].excessiveResets: self.events.add(EventName.localizerMalfunction) # Check if all manager processes are running not_running = { p.name for p in self.sm['managerState'].processes if not p.running } if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) # Only allow engagement with brake pressed when stopped behind another stopped car speeds = self.sm['longitudinalPlan'].speeds if len(speeds) > 1: v_future = speeds[-1] else: v_future = 100.0 if CS.brakePressed and v_future >= self.CP.vEgoStarting \ and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: self.events.add(EventName.noTarget) def data_sample(self): """Receive data from sockets and update carState""" # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) CS = self.CI.update(self.CC, can_strs) self.sm.update(0) if not self.initialized: all_valid = CS.canValid and self.sm.all_checks() if all_valid or self.sm.frame * DT_CTRL > 3.5 or SIMULATION: if not self.read_only: self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) self.initialized = True if REPLAY and self.sm['pandaStates'][0].controlsAllowed: self.state = State.enabled Params().put_bool("ControlsReady", True) # Check for CAN timeout if not can_strs: self.can_rcv_error_counter += 1 self.can_rcv_error = True else: self.can_rcv_error = False # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through # another socket other than the CAN messages and one can arrive earlier than the other. # Therefore we allow a mismatch for two samples, then we trigger the disengagement. if not self.enabled: self.mismatch_counter = 0 # All pandas not in silent mode must have controlsAllowed when openpilot is enabled if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] if ps.safetyModel not in IGNORED_SAFETY_MODES): self.mismatch_counter += 1 self.distance_traveled += CS.vEgo * DT_CTRL return CS def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" self.v_cruise_kph_last = self.v_cruise_kph # if stock cruise is completely disabled, then we can use our own set speed logic if not self.CP.pcmCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.button_timers, self.enabled, self.is_metric) else: if CS.cruiseState.available: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH else: self.v_cruise_kph = 0 # decrement the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state self.soft_disable_timer = max(0, self.soft_disable_timer - 1) self.current_alert_types = [ET.PERMANENT] # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING if self.state != State.disabled: # user and immediate disable always have priority in a non-disabled state if self.events.any(ET.USER_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.USER_DISABLE) elif self.events.any(ET.IMMEDIATE_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.IMMEDIATE_DISABLE) else: # ENABLED if self.state == State.enabled: if self.events.any(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) elif self.events.any(ET.OVERRIDE): self.state = State.overriding self.current_alert_types.append(ET.OVERRIDE) # SOFT DISABLING elif self.state == State.softDisabling: if not self.events.any(ET.SOFT_DISABLE): # no more soft disabling condition, so go back to ENABLED self.state = State.enabled elif self.soft_disable_timer > 0: self.current_alert_types.append(ET.SOFT_DISABLE) elif self.soft_disable_timer <= 0: self.state = State.disabled # PRE ENABLING elif self.state == State.preEnabled: if self.events.any(ET.NO_ENTRY): self.state = State.disabled self.current_alert_types.append(ET.NO_ENTRY) elif not self.events.any(ET.PRE_ENABLE): self.state = State.enabled else: self.current_alert_types.append(ET.PRE_ENABLE) # OVERRIDING elif self.state == State.overriding: if self.events.any(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) self.current_alert_types.append(ET.SOFT_DISABLE) elif not self.events.any(ET.OVERRIDE): self.state = State.enabled else: self.current_alert_types.append(ET.OVERRIDE) # DISABLED elif self.state == State.disabled: if self.events.any(ET.ENABLE): if self.events.any(ET.NO_ENTRY): self.current_alert_types.append(ET.NO_ENTRY) else: if self.events.any(ET.PRE_ENABLE): self.state = State.preEnabled elif self.events.any(ET.OVERRIDE): self.state = State.overriding else: self.state = State.enabled self.current_alert_types.append(ET.ENABLE) if not self.CP.pcmCruise: self.v_cruise_kph = initialize_v_cruise( CS.vEgo, CS.buttonEvents, self.v_cruise_kph_last) # Check if openpilot is engaged and actuators are enabled self.enabled = self.state in ENABLED_STATES self.active = self.state in ACTIVE_STATES if self.active: self.current_alert_types.append(ET.WARNING) def state_control(self, CS): """Given the state, this function returns a CarControl packet""" # Update VehicleModel params = self.sm['liveParameters'] x = max(params.stiffnessFactor, 0.1) sr = max(params.steerRatio, 0.1) self.VM.update_params(x, sr) lat_plan = self.sm['lateralPlan'] long_plan = self.sm['longitudinalPlan'] CC = car.CarControl.new_message() CC.enabled = self.enabled # Check which actuators can be enabled CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ CS.vEgo > self.CP.minSteerSpeed and not CS.standstill CC.longActive = self.active and not self.events.any(ET.OVERRIDE) actuators = CC.actuators actuators.longControlState = self.LoC.long_control_state if CS.leftBlinker or CS.rightBlinker: self.last_blinker_frame = self.sm.frame # State specific actions if not CC.latActive: self.LaC.reset() if not CC.longActive: self.LoC.reset(v_pid=CS.vEgo) if not self.joystick_mode: # accel PID loop pid_accel_limits = self.CI.get_pid_accel_limits( self.CP, CS.vEgo, self.v_cruise_kph * CV.KPH_TO_MS) t_since_plan = (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) * DT_CTRL actuators.accel = self.LoC.update(CC.longActive, CS, self.CP, long_plan, pid_accel_limits, t_since_plan) # Steering PID loop and lateral MPC desired_curvature, desired_curvature_rate = get_lag_adjusted_curvature( self.CP, CS.vEgo, lat_plan.psis, lat_plan.curvatures, lat_plan.curvatureRates) actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update( CC.latActive, CS, self.CP, self.VM, params, self.last_actuators, desired_curvature, desired_curvature_rate) else: lac_log = log.ControlsState.LateralDebugState.new_message() if self.sm.rcv_frame['testJoystick'] > 0: if CC.longActive: actuators.accel = 4.0 * clip( self.sm['testJoystick'].axes[0], -1, 1) if CC.latActive: steer = clip(self.sm['testJoystick'].axes[1], -1, 1) # max angle is 45 for angle-based cars actuators.steer, actuators.steeringAngleDeg = steer, steer * 45. lac_log.active = self.active lac_log.steeringAngleDeg = CS.steeringAngleDeg lac_log.output = actuators.steer lac_log.saturated = abs(actuators.steer) >= 0.9 # Send a "steering required alert" if saturation count has reached the limit if lac_log.active and lac_log.saturated and not CS.steeringPressed: dpath_points = lat_plan.dPathPoints if len(dpath_points): # Check if we deviated from the path # TODO use desired vs actual curvature left_deviation = actuators.steer > 0 and dpath_points[0] < -0.20 right_deviation = actuators.steer < 0 and dpath_points[0] > 0.20 if left_deviation or right_deviation: self.events.add(EventName.steerSaturated) # Ensure no NaNs/Infs for p in ACTUATOR_FIELDS: attr = getattr(actuators, p) if not isinstance(attr, Number): continue if not math.isfinite(attr): cloudlog.error( f"actuators.{p} not finite {actuators.to_dict()}") setattr(actuators, p, 0.0) return CC, lac_log def update_button_timers(self, buttonEvents): # increment timer for buttons still pressed for k in self.button_timers: if self.button_timers[k] > 0: self.button_timers[k] += 1 for b in buttonEvents: if b.type.raw in self.button_timers: self.button_timers[b.type.raw] = 1 if b.pressed else 0 def publish_logs(self, CS, start_time, CC, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller orientation_value = list( self.sm['liveLocationKalman'].calibratedOrientationNED.value) if len(orientation_value) > 2: CC.orientationNED = orientation_value angular_rate_value = list( self.sm['liveLocationKalman'].angularVelocityCalibrated.value) if len(angular_rate_value) > 2: CC.angularVelocity = angular_rate_value CC.cruiseControl.cancel = CS.cruiseState.enabled and ( not self.enabled or not self.CP.pcmCruise) if self.joystick_mode and self.sm.rcv_frame[ 'testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True hudControl = CC.hudControl hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) hudControl.speedVisible = self.enabled hudControl.lanesVisible = self.enabled hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True recent_blinker = (self.sm.frame - self.last_blinker_frame ) * DT_CTRL < 5.0 # 5s blinker cooldown ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ and not CC.latActive and self.sm['liveCalibration'].calStatus == Calibration.CALIBRATED model_v2 = self.sm['modelV2'] desire_prediction = model_v2.meta.desirePrediction if len(desire_prediction) and ldw_allowed: right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 l_lane_change_prob = desire_prediction[Desire.laneChangeLeft - 1] r_lane_change_prob = desire_prediction[Desire.laneChangeRight - 1] lane_lines = model_v2.laneLines l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) hudControl.leftLaneDepart = bool( l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) hudControl.rightLaneDepart = bool( r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) if hudControl.rightLaneDepart or hudControl.leftLaneDepart: self.events.add(EventName.ldw) clear_event_types = set() if ET.WARNING not in self.current_alert_types: clear_event_types.add(ET.WARNING) if self.enabled: clear_event_types.add(ET.NO_ENTRY) alerts = self.events.create_alerts( self.current_alert_types, [self.CP, self.sm, self.is_metric, self.soft_disable_timer]) self.AM.add_many(self.sm.frame, alerts) current_alert = self.AM.process_alerts(self.sm.frame, clear_event_types) if current_alert: hudControl.visualAlert = current_alert.visual_alert if not self.read_only and self.initialized: # send car controls over can self.last_actuators, can_sends = self.CI.apply(CC) self.pm.send( 'sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) CC.actuatorsOutput = self.last_actuators force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) # Curvature & Steering angle params = self.sm['liveParameters'] steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetDeg) curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, params.roll) # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid controlsState = dat.controlsState if current_alert: controlsState.alertText1 = current_alert.alert_text_1 controlsState.alertText2 = current_alert.alert_text_2 controlsState.alertSize = current_alert.alert_size controlsState.alertStatus = current_alert.alert_status controlsState.alertBlinkingRate = current_alert.alert_rate controlsState.alertType = current_alert.alert_type controlsState.alertSound = current_alert.audible_alert controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime[ 'longitudinalPlan'] controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.curvature = curvature controlsState.state = self.state controlsState.engageable = not self.events.any(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state controlsState.vPid = float(self.LoC.v_pid) controlsState.vCruise = float(self.v_cruise_kph) controlsState.upAccelCmd = float(self.LoC.pid.p) controlsState.uiAccelCmd = float(self.LoC.pid.i) controlsState.ufAccelCmd = float(self.LoC.pid.f) controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_rcv_error_counter lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: controlsState.lateralControlState.debugState = lac_log elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log elif lat_tuning == 'pid': controlsState.lateralControlState.pidState = lac_log elif lat_tuning == 'lqr': controlsState.lateralControlState.lqrState = lac_log elif lat_tuning == 'indi': controlsState.lateralControlState.indiState = lac_log self.pm.send('controlsState', dat) # carState car_events = self.events.to_msg() cs_send = messaging.new_message('carState') cs_send.valid = CS.canValid cs_send.carState = CS cs_send.carState.events = car_events self.pm.send('carState', cs_send) # carEvents - logged every second or on change if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): ce_send = messaging.new_message('carEvents', len(self.events)) ce_send.carEvents = car_events self.pm.send('carEvents', ce_send) self.events_prev = self.events.names.copy() # carParams - logged every 50 seconds (> 1 per segment) if (self.sm.frame % int(50. / DT_CTRL) == 0): cp_send = messaging.new_message('carParams') cp_send.carParams = self.CP self.pm.send('carParams', cp_send) # carControl cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid cc_send.carControl = CC self.pm.send('carControl', cc_send) # copy CarControl to pass to CarInterface on the next iteration self.CC = CC def step(self): start_time = sec_since_boot() self.prof.checkpoint("Ratekeeper", ignore=True) # Sample data from sockets and get a carState CS = self.data_sample() cloudlog.timestamp("Data sampled") self.prof.checkpoint("Sample") self.update_events(CS) cloudlog.timestamp("Events updated") if not self.read_only and self.initialized: # Update control state self.state_transition(CS) self.prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) CC, lac_log = self.state_control(CS) self.prof.checkpoint("State Control") # Publish data self.publish_logs(CS, start_time, CC, lac_log) self.prof.checkpoint("Sent") self.update_button_timers(CS.buttonEvents) self.CS_prev = CS def controlsd_thread(self): while True: self.step() self.rk.monitor_time() self.prof.display()
class Controls: def __init__(self, sm=None, pm=None, can_sock=None): config_realtime_process(4 if TICI else 3, Priority.CTRL_HIGH) # Setup sockets self.pm = pm if self.pm is None: self.pm = messaging.PubMaster([ 'sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams' ]) self.camera_packets = ["roadCameraState", "driverCameraState"] if TICI: self.camera_packets.append("wideRoadCameraState") params = Params() self.joystick_mode = params.get_bool("JoystickDebugMode") joystick_packet = ['testJoystick'] if self.joystick_mode else [] self.sm = sm if self.sm is None: ignore = ['driverCameraState', 'managerState' ] if SIMULATION else None self.sm = messaging.SubMaster( [ 'deviceState', 'pandaState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', 'managerState', 'liveParameters', 'radarState' ] + self.camera_packets + joystick_packet, ignore_alive=ignore, ignore_avg_freq=['radarState', 'longitudinalPlan']) self.can_sock = can_sock if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 self.can_sock = messaging.sub_sock('can', timeout=can_timeout) if TICI: self.log_sock = messaging.sub_sock('androidLog') # wait for one pandaState and one CAN packet print("Waiting for CAN messages...") get_one_can(self.can_sock) self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan']) # read params self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") community_feature_toggle = params.get_bool("CommunityFeaturesToggle") openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") passive = params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' controller_available = self.CI.CC is not None and not passive and not self.CP.dashcamOnly community_feature = self.CP.communityFeature or \ self.CP.fingerprintSource == car.CarParams.FingerprintSource.can community_feature_disallowed = community_feature and ( not community_feature_toggle) self.read_only = not car_recognized or not controller_available or \ self.CP.dashcamOnly or community_feature_disallowed if self.read_only: self.CP.safetyModel = car.CarParams.SafetyModel.noOutput # Write CarParams for radard cp_bytes = self.CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) self.CC = car.CarControl.new_message() self.AM = AlertManager() self.events = Events() self.LoC = LongControl(self.CP, self.CI.compute_gb) self.VM = VehicleModel(self.CP) if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP) elif self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP) elif self.CP.lateralTuning.which() == 'indi': self.LaC = LatControlINDI(self.CP) elif self.CP.lateralTuning.which() == 'lqr': self.LaC = LatControlLQR(self.CP) self.initialized = False self.state = State.disabled self.enabled = False self.active = False self.can_rcv_error = False self.soft_disable_timer = 0 self.v_cruise_kph = 255 self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.can_error_counter = 0 self.last_blinker_frame = 0 self.saturated_count = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = False self.v_target = 0.0 self.a_target = 0.0 # TODO: no longer necessary, aside from process replay self.sm['liveParameters'].valid = True self.startup_event = get_startup_event(car_recognized, controller_available, self.CP.fuzzyFingerprint, len(self.CP.carFw) > 0) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if community_feature_disallowed and car_recognized and not self.CP.dashcamOnly: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) elif self.read_only: self.events.add(EventName.dashcamMode, static=True) elif self.joystick_mode: self.events.add(EventName.joystickDebug, static=True) self.startup_event = None # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default def update_events(self, CS): """Compute carEvents from carState""" self.events.clear() self.events.add_from_msg(CS.events) self.events.add_from_msg(self.sm['driverMonitoringState'].events) # Handle startup event if self.startup_event is not None: self.events.add(self.startup_event) self.startup_event = None # Don't add any more events if not initialized if not self.initialized: self.events.add(EventName.controlsInitializing) return # Create events for battery, temperature, disk space, and memory if self.sm['deviceState'].batteryPercent < 1 and self.sm[ 'deviceState'].chargingError: # at zero percent battery, while discharging, OP should not allowed self.events.add(EventName.lowBattery) if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) # TODO: make tici threshold the same if self.sm['deviceState'].memoryUsagePercent > (90 if TICI else 65) and not SIMULATION: self.events.add(EventName.lowMemory) # Alert if fan isn't spinning for 5 seconds if self.sm['pandaState'].pandaType in [PandaType.uno, PandaType.dos]: if self.sm['pandaState'].fanSpeedRpm == 0 and self.sm[ 'deviceState'].fanSpeedPercentDesired > 50: if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0: self.events.add(EventName.fanMalfunction) else: self.last_functional_fan_frame = self.sm.frame # Handle calibration status cal_status = self.sm['liveCalibration'].calStatus if cal_status != Calibration.CALIBRATED: if cal_status == Calibration.UNCALIBRATED: self.events.add(EventName.calibrationIncomplete) else: self.events.add(EventName.calibrationInvalid) # Handle lane change if self.sm[ 'lateralPlan'].laneChangeState == LaneChangeState.preLaneChange: direction = self.sm['lateralPlan'].laneChangeDirection if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ (CS.rightBlindspot and direction == LaneChangeDirection.right): self.events.add(EventName.laneChangeBlocked) else: if direction == LaneChangeDirection.left: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) elif self.sm['lateralPlan'].laneChangeState in [ LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing ]: self.events.add(EventName.laneChange) if self.can_rcv_error or not CS.canValid: self.events.add(EventName.canError) safety_mismatch = self.sm[ 'pandaState'].safetyModel != self.CP.safetyModel or self.sm[ 'pandaState'].safetyParam != self.CP.safetyParam if safety_mismatch or self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm['liveParameters'].valid: self.events.add(EventName.vehicleModelInvalid) if len(self.sm['radarState'].radarErrors): self.events.add(EventName.radarFault) elif not self.sm.valid["pandaState"]: self.events.add(EventName.usbError) elif not self.sm.all_alive_and_valid(): self.events.add(EventName.commIssue) if not self.logged_comm_issue: invalid = [ s for s, valid in self.sm.valid.items() if not valid ] not_alive = [ s for s, alive in self.sm.alive.items() if not alive ] cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive) self.logged_comm_issue = True else: self.logged_comm_issue = False if not self.sm['lateralPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) if not self.sm['liveLocationKalman'].sensorsOK and not NOSENSOR: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) if not self.sm['liveLocationKalman'].deviceStable: self.events.add(EventName.deviceFalling) if log.PandaState.FaultType.relayMalfunction in self.sm[ 'pandaState'].faults: self.events.add(EventName.relayMalfunction) if self.sm['longitudinalPlan'].fcw or ( self.enabled and self.sm['modelV2'].meta.hardBrakePredicted): self.events.add(EventName.fcw) if TICI: logs = messaging.drain_sock(self.log_sock, wait_for_one=False) messages = [] for m in logs: try: messages.append(m.androidLog.message) except UnicodeDecodeError: pass for err in [ "ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED" ]: for m in messages: if err not in m: continue csid = m.split("CSID:")[-1].split(" ")[0] evt = { "0": EventName.roadCameraError, "1": EventName.wideRoadCameraError, "2": EventName.driverCameraError }.get(csid, None) if evt is not None: self.events.add(evt) # TODO: fix simulator if not SIMULATION: if not NOSENSOR: if not self.sm['liveLocationKalman'].gpsOK and ( self.distance_traveled > 1000): # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes self.events.add(EventName.noGps) if not self.sm.all_alive(self.camera_packets): self.events.add(EventName.cameraMalfunction) if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) if self.sm['liveLocationKalman'].excessiveResets: self.events.add(EventName.localizerMalfunction) # Check if all manager processes are running not_running = set(p.name for p in self.sm['managerState'].processes if not p.running) if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) # Only allow engagement with brake pressed when stopped behind another stopped car speeds = self.sm['longitudinalPlan'].speeds if len(speeds) > 1: v_future = speeds[-1] else: v_future = 100.0 if CS.brakePressed and v_future >= STARTING_TARGET_SPEED \ and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: self.events.add(EventName.noTarget) def data_sample(self): """Receive data from sockets and update carState""" # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) CS = self.CI.update(self.CC, can_strs) self.sm.update(0) all_valid = CS.canValid and self.sm.all_alive_and_valid() if not self.initialized and (all_valid or self.sm.frame * DT_CTRL > 2.0): self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) self.initialized = True Params().put_bool("ControlsReady", True) # Check for CAN timeout if not can_strs: self.can_error_counter += 1 self.can_rcv_error = True else: self.can_rcv_error = False # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through # another socket other than the CAN messages and one can arrive earlier than the other. # Therefore we allow a mismatch for two samples, then we trigger the disengagement. if not self.enabled: self.mismatch_counter = 0 if not self.sm['pandaState'].controlsAllowed and self.enabled: self.mismatch_counter += 1 self.distance_traveled += CS.vEgo * DT_CTRL return CS def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" self.v_cruise_kph_last = self.v_cruise_kph # if stock cruise is completely disabled, then we can use our own set speed logic if not self.CP.pcmCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.enabled) elif self.CP.pcmCruise and CS.cruiseState.enabled: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # decrease the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state self.soft_disable_timer = max(0, self.soft_disable_timer - 1) self.current_alert_types = [ET.PERMANENT] # ENABLED, PRE ENABLING, SOFT DISABLING if self.state != State.disabled: # user and immediate disable always have priority in a non-disabled state if self.events.any(ET.USER_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.USER_DISABLE) elif self.events.any(ET.IMMEDIATE_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.IMMEDIATE_DISABLE) else: # ENABLED if self.state == State.enabled: if self.events.any(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = 300 # 3s self.current_alert_types.append(ET.SOFT_DISABLE) # SOFT DISABLING elif self.state == State.softDisabling: if not self.events.any(ET.SOFT_DISABLE): # no more soft disabling condition, so go back to ENABLED self.state = State.enabled elif self.events.any( ET.SOFT_DISABLE) and self.soft_disable_timer > 0: self.current_alert_types.append(ET.SOFT_DISABLE) elif self.soft_disable_timer <= 0: self.state = State.disabled # PRE ENABLING elif self.state == State.preEnabled: if not self.events.any(ET.PRE_ENABLE): self.state = State.enabled else: self.current_alert_types.append(ET.PRE_ENABLE) # DISABLED elif self.state == State.disabled: if self.events.any(ET.ENABLE): if self.events.any(ET.NO_ENTRY): self.current_alert_types.append(ET.NO_ENTRY) else: if self.events.any(ET.PRE_ENABLE): self.state = State.preEnabled else: self.state = State.enabled self.current_alert_types.append(ET.ENABLE) self.v_cruise_kph = initialize_v_cruise( CS.vEgo, CS.buttonEvents, self.v_cruise_kph_last) # Check if actuators are enabled self.active = self.state == State.enabled or self.state == State.softDisabling if self.active: self.current_alert_types.append(ET.WARNING) # Check if openpilot is engaged self.enabled = self.active or self.state == State.preEnabled def state_control(self, CS): """Given the state, this function returns an actuators packet""" # Update VehicleModel params = self.sm['liveParameters'] x = max(params.stiffnessFactor, 0.1) sr = max(params.steerRatio, 0.1) self.VM.update_params(x, sr) lat_plan = self.sm['lateralPlan'] long_plan = self.sm['longitudinalPlan'] actuators = car.CarControl.Actuators.new_message() if CS.leftBlinker or CS.rightBlinker: self.last_blinker_frame = self.sm.frame # State specific actions if not self.active: self.LaC.reset() self.LoC.reset(v_pid=CS.vEgo) if not self.joystick_mode: # Gas/Brake PID loop actuators.gas, actuators.brake, self.v_target, self.a_target = self.LoC.update( self.active, CS, self.CP, long_plan) # Steering PID loop and lateral MPC desired_curvature, desired_curvature_rate = get_lag_adjusted_curvature( self.CP, CS.vEgo, lat_plan.psis, lat_plan.curvatures, lat_plan.curvatureRates) actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update( self.active, CS, self.CP, self.VM, params, desired_curvature, desired_curvature_rate) else: lac_log = log.ControlsState.LateralDebugState.new_message() if self.sm.rcv_frame['testJoystick'] > 0 and self.active: gb = clip(self.sm['testJoystick'].axes[0], -1, 1) actuators.gas, actuators.brake = max(gb, 0), max(-gb, 0) steer = clip(self.sm['testJoystick'].axes[1], -1, 1) # max angle is 45 for angle-based cars actuators.steer, actuators.steeringAngleDeg = steer, steer * 45. lac_log.active = True lac_log.steeringAngleDeg = CS.steeringAngleDeg lac_log.output = steer lac_log.saturated = abs(steer) >= 0.9 # Check for difference between desired angle and angle for angle based control angle_control_saturated = self.CP.steerControlType == car.CarParams.SteerControlType.angle and \ abs(actuators.steeringAngleDeg - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD if angle_control_saturated and not CS.steeringPressed and self.active: self.saturated_count += 1 else: self.saturated_count = 0 # Send a "steering required alert" if saturation count has reached the limit if (lac_log.saturated and not CS.steeringPressed) or \ (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): if len(lat_plan.dPathPoints): # Check if we deviated from the path left_deviation = actuators.steer > 0 and lat_plan.dPathPoints[ 0] < -0.1 right_deviation = actuators.steer < 0 and lat_plan.dPathPoints[ 0] > 0.1 if left_deviation or right_deviation: self.events.add(EventName.steerSaturated) return actuators, lac_log def publish_logs(self, CS, start_time, actuators, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" CC = car.CarControl.new_message() CC.enabled = self.enabled CC.actuators = actuators CC.cruiseControl.override = True CC.cruiseControl.cancel = not self.CP.pcmCruise or ( not self.enabled and CS.cruiseState.enabled) if self.joystick_mode and self.sm.rcv_frame[ 'testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True # TODO remove car specific stuff in controls # Some override values for Honda # brake discount removes a sharp nonlinearity brake_discount = (1.0 - clip(actuators.brake * 3., 0.0, 1.0)) speed_override = max(0.0, (self.LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) CC.cruiseControl.speedOverride = float( speed_override if self.CP.pcmCruise else 0.0) CC.cruiseControl.accelOverride = float( self.CI.calc_accel_override(CS.aEgo, self.a_target, CS.vEgo, self.v_target)) CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = self.enabled CC.hudControl.lanesVisible = self.enabled CC.hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 CC.hudControl.rightLaneVisible = bool(right_lane_visible) CC.hudControl.leftLaneVisible = bool(left_lane_visible) recent_blinker = (self.sm.frame - self.last_blinker_frame ) * DT_CTRL < 5.0 # 5s blinker cooldown ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ and not self.active and self.sm['liveCalibration'].calStatus == Calibration.CALIBRATED meta = self.sm['modelV2'].meta if len(meta.desirePrediction) and ldw_allowed: l_lane_change_prob = meta.desirePrediction[Desire.laneChangeLeft - 1] r_lane_change_prob = meta.desirePrediction[Desire.laneChangeRight - 1] l_lane_close = left_lane_visible and ( self.sm['modelV2'].laneLines[1].y[0] > -(1.08 + CAMERA_OFFSET)) r_lane_close = right_lane_visible and ( self.sm['modelV2'].laneLines[2].y[0] < (1.08 - CAMERA_OFFSET)) CC.hudControl.leftLaneDepart = bool( l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) CC.hudControl.rightLaneDepart = bool( r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) if CC.hudControl.rightLaneDepart or CC.hudControl.leftLaneDepart: self.events.add(EventName.ldw) clear_event = ET.WARNING if ET.WARNING not in self.current_alert_types else None alerts = self.events.create_alerts(self.current_alert_types, [self.CP, self.sm, self.is_metric]) self.AM.add_many(self.sm.frame, alerts, self.enabled) self.AM.process_alerts(self.sm.frame, clear_event) CC.hudControl.visualAlert = self.AM.visual_alert if not self.read_only and self.initialized: # send car controls over can can_sends = self.CI.apply(CC) self.pm.send( 'sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) # Curvature & Steering angle params = self.sm['liveParameters'] steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetAverageDeg) curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo) # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid controlsState = dat.controlsState controlsState.alertText1 = self.AM.alert_text_1 controlsState.alertText2 = self.AM.alert_text_2 controlsState.alertSize = self.AM.alert_size controlsState.alertStatus = self.AM.alert_status controlsState.alertBlinkingRate = self.AM.alert_rate controlsState.alertType = self.AM.alert_type controlsState.alertSound = self.AM.audible_alert controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime[ 'longitudinalPlan'] controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.curvature = curvature controlsState.state = self.state controlsState.engageable = not self.events.any(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state controlsState.vPid = float(self.LoC.v_pid) controlsState.vCruise = float(self.v_cruise_kph) controlsState.upAccelCmd = float(self.LoC.pid.p) controlsState.uiAccelCmd = float(self.LoC.pid.i) controlsState.ufAccelCmd = float(self.LoC.pid.f) controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_error_counter if self.joystick_mode: controlsState.lateralControlState.debugState = lac_log elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log elif self.CP.lateralTuning.which() == 'pid': controlsState.lateralControlState.pidState = lac_log elif self.CP.lateralTuning.which() == 'lqr': controlsState.lateralControlState.lqrState = lac_log elif self.CP.lateralTuning.which() == 'indi': controlsState.lateralControlState.indiState = lac_log self.pm.send('controlsState', dat) # carState car_events = self.events.to_msg() cs_send = messaging.new_message('carState') cs_send.valid = CS.canValid cs_send.carState = CS cs_send.carState.events = car_events self.pm.send('carState', cs_send) # carEvents - logged every second or on change if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): ce_send = messaging.new_message('carEvents', len(self.events)) ce_send.carEvents = car_events self.pm.send('carEvents', ce_send) self.events_prev = self.events.names.copy() # carParams - logged every 50 seconds (> 1 per segment) if (self.sm.frame % int(50. / DT_CTRL) == 0): cp_send = messaging.new_message('carParams') cp_send.carParams = self.CP self.pm.send('carParams', cp_send) # carControl cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid cc_send.carControl = CC self.pm.send('carControl', cc_send) # copy CarControl to pass to CarInterface on the next iteration self.CC = CC def step(self): start_time = sec_since_boot() self.prof.checkpoint("Ratekeeper", ignore=True) # Sample data from sockets and get a carState CS = self.data_sample() self.prof.checkpoint("Sample") self.update_events(CS) if not self.read_only and self.initialized: # Update control state self.state_transition(CS) self.prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, lac_log = self.state_control(CS) self.prof.checkpoint("State Control") # Publish data self.publish_logs(CS, start_time, actuators, lac_log) self.prof.checkpoint("Sent") def controlsd_thread(self): while True: self.step() self.rk.monitor_time() self.prof.display()
def radard_thread(gctx=None): set_realtime_priority(2) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) mocked = CP.carName == "mock" VM = VehicleModel(CP) cloudlog.info("radard got CarParams") # import the radar from the fingerprint cloudlog.info("radard is importing %s", CP.carName) RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % CP.carName).RadarInterface sm = messaging.SubMaster(['model', 'controlsState', 'liveParameters']) # Default parameters live_parameters = messaging.new_message() live_parameters.init('liveParameters') live_parameters.liveParameters.valid = True live_parameters.liveParameters.steerRatio = CP.steerRatio live_parameters.liveParameters.stiffnessFactor = 1.0 MP = ModelParser() RI = RadarInterface(CP) last_md_ts = 0 last_controls_state_ts = 0 # *** publish radarState and liveTracks radarState = messaging.pub_sock(service_list['radarState'].port) liveTracks = messaging.pub_sock(service_list['liveTracks'].port) path_x = np.arange(0.0, 140.0, 0.1) # 140 meters is max # Time-alignment rate = 1. / DT_MDL # model and radar are both at 20Hz v_len = 20 # how many speed data points to remember for t alignment with rdr data active = 0 steer_angle = 0. steer_override = False tracks = defaultdict(dict) # Kalman filter stuff: ekfv = EKFV1D() speedSensorV = SimpleSensor(XV, 1, 2) # v_ego v_ego = 0. v_ego_hist_t = deque([0], maxlen=v_len) v_ego_hist_v = deque([0], maxlen=v_len) v_ego_t_aligned = 0. rk = Ratekeeper(rate, print_delay_threshold=None) while 1: rr = RI.update() ar_pts = {} for pt in rr.points: ar_pts[pt.trackId] = [pt.dRel + RDR_TO_LDR, pt.yRel, pt.vRel, pt.measured] sm.update(0) if sm.updated['liveParameters']: VM.update_params(sm['liveParameters'].stiffnessFactor, sm['liveParameters'].steerRatio) if sm.updated['controlsState']: active = sm['controlsState'].active v_ego = sm['controlsState'].vEgo steer_angle = sm['controlsState'].angleSteers steer_override = sm['controlsState'].steerOverride v_ego_hist_v.append(v_ego) v_ego_hist_t.append(float(rk.frame)/rate) last_controls_state_ts = sm.logMonoTime['controlsState'] if sm.updated['model']: last_md_ts = sm.logMonoTime['model'] MP.update(v_ego, sm['model']) # run kalman filter only if prob is high enough if MP.lead_prob > 0.7: reading = speedSensorV.read(MP.lead_dist, covar=np.matrix(MP.lead_var)) ekfv.update_scalar(reading) ekfv.predict(DT_MDL) # When changing lanes the distance to the lead car can suddenly change, # which makes the Kalman filter output large relative acceleration if mocked and abs(MP.lead_dist - ekfv.state[XV]) > 2.0: ekfv.state[XV] = MP.lead_dist ekfv.covar = (np.diag([MP.lead_var, ekfv.var_init])) ekfv.state[SPEEDV] = 0. ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(MP.d_poly, float(ekfv.state[XV])), float(ekfv.state[SPEEDV]), False) else: ekfv.state[XV] = MP.lead_dist ekfv.covar = (np.diag([MP.lead_var, ekfv.var_init])) ekfv.state[SPEEDV] = 0. if VISION_POINT in ar_pts: del ar_pts[VISION_POINT] # *** compute the likely path_y *** if (active and not steer_override) or mocked: # use path from model (always when mocking as steering is too noisy) path_y = np.polyval(MP.d_poly, path_x) else: # use path from steer, set angle_offset to 0 it does not only report the physical offset path_y = calc_lookahead_offset(v_ego, steer_angle, path_x, VM, angle_offset=live_parameters.liveParameters.angleOffsetAverage)[0] # *** remove missing points from meta data *** for ids in tracks.keys(): if ids not in ar_pts: tracks.pop(ids, None) # *** compute the tracks *** for ids in ar_pts: # ignore standalone vision point, unless we are mocking the radar if ids == VISION_POINT and not mocked: continue rpt = ar_pts[ids] # align v_ego by a fixed time to align it with the radar measurement cur_time = float(rk.frame)/rate v_ego_t_aligned = np.interp(cur_time - RI.delay, v_ego_hist_t, v_ego_hist_v) d_path = np.sqrt(np.amin((path_x - rpt[0]) ** 2 + (path_y - rpt[1]) ** 2)) # add sign d_path *= np.sign(rpt[1] - np.interp(rpt[0], path_x, path_y)) # create the track if it doesn't exist or it's a new track if ids not in tracks: tracks[ids] = Track() tracks[ids].update(rpt[0], rpt[1], rpt[2], d_path, v_ego_t_aligned, rpt[3], steer_override) # allow the vision model to remove the stationary flag if distance and rel speed roughly match if VISION_POINT in ar_pts: fused_id = None best_score = NO_FUSION_SCORE for ids in tracks: dist_to_vision = np.sqrt((0.5*(ar_pts[VISION_POINT][0] - tracks[ids].dRel)) ** 2 + (2*(ar_pts[VISION_POINT][1] - tracks[ids].yRel)) ** 2) rel_speed_diff = abs(ar_pts[VISION_POINT][2] - tracks[ids].vRel) tracks[ids].update_vision_score(dist_to_vision, rel_speed_diff) if best_score > tracks[ids].vision_score: fused_id = ids best_score = tracks[ids].vision_score if fused_id is not None: tracks[fused_id].vision_cnt += 1 tracks[fused_id].update_vision_fusion() if DEBUG: print("NEW CYCLE") if VISION_POINT in ar_pts: print("vision", ar_pts[VISION_POINT]) idens = list(tracks.keys()) track_pts = np.array([tracks[iden].get_key_for_cluster() for iden in idens]) # If we have multiple points, cluster them if len(track_pts) > 1: cluster_idxs = cluster_points_centroid(track_pts, 2.5) clusters = [None] * (max(cluster_idxs) + 1) for idx in xrange(len(track_pts)): cluster_i = cluster_idxs[idx] if clusters[cluster_i] is None: clusters[cluster_i] = Cluster() clusters[cluster_i].add(tracks[idens[idx]]) elif len(track_pts) == 1: # TODO: why do we need this? clusters = [Cluster()] clusters[0].add(tracks[idens[0]]) else: clusters = [] if DEBUG: for i in clusters: print(i) # *** extract the lead car *** lead_clusters = [c for c in clusters if c.is_potential_lead(v_ego)] lead_clusters.sort(key=lambda x: x.dRel) lead_len = len(lead_clusters) # *** extract the second lead from the whole set of leads *** lead2_clusters = [c for c in lead_clusters if c.is_potential_lead2(lead_clusters)] lead2_clusters.sort(key=lambda x: x.dRel) lead2_len = len(lead2_clusters) # *** publish radarState *** dat = messaging.new_message() dat.init('radarState') dat.valid = sm.all_alive_and_valid(service_list=['controlsState']) dat.radarState.mdMonoTime = last_md_ts dat.radarState.canMonoTimes = list(rr.canMonoTimes) dat.radarState.radarErrors = list(rr.errors) dat.radarState.controlsStateMonoTime = last_controls_state_ts if lead_len > 0: dat.radarState.leadOne = lead_clusters[0].toRadarState() if lead2_len > 0: dat.radarState.leadTwo = lead2_clusters[0].toRadarState() else: dat.radarState.leadTwo.status = False else: dat.radarState.leadOne.status = False dat.radarState.cumLagMs = -rk.remaining*1000. radarState.send(dat.to_bytes()) # *** publish tracks for UI debugging (keep last) *** dat = messaging.new_message() dat.init('liveTracks', len(tracks)) for cnt, ids in enumerate(tracks.keys()): if DEBUG: print("id: %4.0f x: %4.1f y: %4.1f vr: %4.1f d: %4.1f va: %4.1f vl: %4.1f vlk: %4.1f alk: %4.1f s: %1.0f v: %1.0f" % \ (ids, tracks[ids].dRel, tracks[ids].yRel, tracks[ids].vRel, tracks[ids].dPath, tracks[ids].vLat, tracks[ids].vLead, tracks[ids].vLeadK, tracks[ids].aLeadK, tracks[ids].stationary, tracks[ids].measured)) dat.liveTracks[cnt] = { "trackId": ids, "dRel": float(tracks[ids].dRel), "yRel": float(tracks[ids].yRel), "vRel": float(tracks[ids].vRel), "aRel": float(tracks[ids].aRel), "stationary": bool(tracks[ids].stationary), "oncoming": bool(tracks[ids].oncoming), } liveTracks.send(dat.to_bytes()) rk.monitor_time()
class Controls: def __init__(self, sm=None, pm=None, can_sock=None): config_realtime_process(3, Priority.CTRL_HIGH) # Setup sockets self.pm = pm if self.pm is None: self.pm = messaging.PubMaster(['sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams']) self.sm = sm if self.sm is None: ignore = ['driverCameraState', 'managerState'] if SIMULATION else None self.sm = messaging.SubMaster(['deviceState', 'pandaState', 'modelV2', 'liveCalibration', 'driverMonitoringState', 'longitudinalPlan', 'lateralPlan', 'liveLocationKalman', 'roadCameraState', 'driverCameraState', 'managerState', 'liveParameters', 'radarState'], ignore_alive=ignore) self.can_sock = can_sock if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 self.can_sock = messaging.sub_sock('can', timeout=can_timeout) # wait for one pandaState and one CAN packet hw_type = messaging.recv_one(self.sm.sock['pandaState']).pandaState.pandaType has_relay = hw_type in [PandaType.blackPanda, PandaType.uno, PandaType.dos] print("Waiting for CAN messages...") get_one_can(self.can_sock) self.CI, self.CP = get_car(self.can_sock, self.pm.sock['sendcan'], has_relay) # read params params = Params() self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") community_feature_toggle = params.get_bool("CommunityFeaturesToggle") openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") passive = params.get_bool("Passive") or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = HARDWARE.get_sound_card_online() car_recognized = self.CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not dashcam mode controller_available = self.CP.enableCamera and self.CI.CC is not None and not passive and not self.CP.dashcamOnly community_feature_disallowed = self.CP.communityFeature and not community_feature_toggle self.read_only = not car_recognized or not controller_available or \ self.CP.dashcamOnly or community_feature_disallowed if self.read_only: self.CP.safetyModel = car.CarParams.SafetyModel.noOutput # Write CarParams for radard and boardd safety mode cp_bytes = self.CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) self.CC = car.CarControl.new_message() self.AM = AlertManager() self.events = Events() self.LoC = LongControl(self.CP, self.CI.compute_gb) self.VM = VehicleModel(self.CP) if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP) elif self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP) elif self.CP.lateralTuning.which() == 'indi': self.LaC = LatControlINDI(self.CP) elif self.CP.lateralTuning.which() == 'lqr': self.LaC = LatControlLQR(self.CP) self.state = State.disabled self.enabled = False self.active = False self.can_rcv_error = False self.soft_disable_timer = 0 self.v_cruise_kph = 255 self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.can_error_counter = 0 self.last_blinker_frame = 0 self.saturated_count = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = False # scc smoother self.is_cruise_enabled = False self.cruiseVirtualMaxSpeed = 0 self.clu_speed_ms = 0. self.apply_accel = 0. self.fused_accel = 0. self.lead_drel = 0. self.aReqValue = 0. self.aReqValueMin = 0. self.aReqValueMax = 0. self.angle_steers_des = 0. self.sm['liveCalibration'].calStatus = Calibration.CALIBRATED self.sm['deviceState'].freeSpacePercent = 100 self.sm['driverMonitoringState'].events = [] self.sm['driverMonitoringState'].awarenessStatus = 1. self.sm['driverMonitoringState'].faceDetected = False self.sm['liveParameters'].valid = True self.startup_event = get_startup_event(car_recognized, controller_available, hw_type) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) elif self.read_only: self.events.add(EventName.dashcamMode, static=True) # controlsd is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) self.prof = Profiler(False) # off by default def update_events(self, CS): """Compute carEvents from carState""" self.events.clear() self.events.add_from_msg(CS.events) self.events.add_from_msg(self.sm['driverMonitoringState'].events) # Handle startup event if self.startup_event is not None: self.events.add(self.startup_event) self.startup_event = None # Create events for battery, temperature, disk space, and memory if self.sm['deviceState'].batteryPercent < 1 and self.sm['deviceState'].chargingError: # at zero percent battery, while discharging, OP should not allowed self.events.add(EventName.lowBattery) if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['deviceState'].freeSpacePercent < 7: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) if self.sm['deviceState'].memoryUsagePercent > 90: self.events.add(EventName.lowMemory) # Alert if fan isn't spinning for 5 seconds if self.sm['pandaState'].pandaType in [PandaType.uno, PandaType.dos]: if self.sm['pandaState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50: if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0: self.events.add(EventName.fanMalfunction) else: self.last_functional_fan_frame = self.sm.frame # Handle calibration status cal_status = self.sm['liveCalibration'].calStatus if cal_status != Calibration.CALIBRATED: if cal_status == Calibration.UNCALIBRATED: self.events.add(EventName.calibrationIncomplete) else: self.events.add(EventName.calibrationInvalid) # Handle lane change if self.sm['lateralPlan'].laneChangeState == LaneChangeState.preLaneChange: direction = self.sm['lateralPlan'].laneChangeDirection if (CS.leftBlindspot and direction == LaneChangeDirection.left) or \ (CS.rightBlindspot and direction == LaneChangeDirection.right): self.events.add(EventName.laneChangeBlocked) elif self.sm['lateralPlan'].autoLaneChangeEnabled and self.sm['lateralPlan'].autoLaneChangeTimer > 0: self.events.add(EventName.autoLaneChange) else: if direction == LaneChangeDirection.left: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) elif self.sm['lateralPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) if self.can_rcv_error or (not CS.canValid and self.sm.frame > 5 / DT_CTRL): self.events.add(EventName.canError) safety_mismatch = self.sm['pandaState'].safetyModel != self.CP.safetyModel safety_mismatch = safety_mismatch or self.sm['pandaState'].safetyParam != self.CP.safetyParam if (safety_mismatch and self.sm.frame > 2 / DT_CTRL) or self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm['liveParameters'].valid: self.events.add(EventName.vehicleModelInvalid) if len(self.sm['radarState'].radarErrors): self.events.add(EventName.radarFault) elif not self.sm.all_alive_and_valid(): self.events.add(EventName.commIssue) if not self.logged_comm_issue: cloudlog.error(f"commIssue - valid: {self.sm.valid} - alive: {self.sm.alive}") self.logged_comm_issue = True else: self.logged_comm_issue = False if not self.sm['lateralPlan'].mpcSolutionValid and not (EventName.turningIndicatorOn in self.events.names): self.events.add(EventName.plannerError) if not self.sm['liveLocationKalman'].sensorsOK and not NOSENSOR: if self.sm.frame > 5 / DT_CTRL: # Give locationd some time to receive all the inputs self.events.add(EventName.sensorDataInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) if not self.sm['liveLocationKalman'].deviceStable: self.events.add(EventName.deviceFalling) if log.PandaState.FaultType.relayMalfunction in self.sm['pandaState'].faults: self.events.add(EventName.relayMalfunction) if self.sm['longitudinalPlan'].fcw: self.events.add(EventName.fcw) # TODO: fix simulator if not SIMULATION: #if not NOSENSOR: #if not self.sm['liveLocationKalman'].gpsOK and (self.distance_traveled > 1000) and not TICI: # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes #self.events.add(EventName.noGps) if not self.sm.all_alive(['roadCameraState', 'driverCameraState']) and (self.sm.frame > 5 / DT_CTRL): self.events.add(EventName.cameraMalfunction) if self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) # Check if all manager processes are running not_running = set(p.name for p in self.sm['managerState'].processes if not p.running) if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) # Only allow engagement with brake pressed when stopped behind another stopped car #if CS.brakePressed and self.sm['longitudinalPlan'].vTargetFuture >= STARTING_TARGET_SPEED \ #and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: #self.events.add(EventName.noTarget) def data_sample(self): """Receive data from sockets and update carState""" # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) CS = self.CI.update(self.CC, can_strs) self.sm.update(0) # Check for CAN timeout if not can_strs: self.can_error_counter += 1 self.can_rcv_error = True else: self.can_rcv_error = False # When the panda and controlsd do not agree on controls_allowed # we want to disengage openpilot. However the status from the panda goes through # another socket other than the CAN messages and one can arrive earlier than the other. # Therefore we allow a mismatch for two samples, then we trigger the disengagement. if not self.enabled: self.mismatch_counter = 0 if not self.sm['pandaState'].controlsAllowed and self.enabled: self.mismatch_counter += 1 self.distance_traveled += CS.vEgo * DT_CTRL return CS def state_transition(self, CS): """Compute conditional state transitions and execute actions on state transitions""" self.v_cruise_kph_last = self.v_cruise_kph # if stock cruise is completely disabled, then we can use our own set speed logic self.CP.enableCruise = self.CI.CP.enableCruise #if not self.CP.enableCruise: # self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.enabled, self.is_metric) #elif self.CP.enableCruise and CS.cruiseState.enabled: # self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # scc smoother SccSmoother.update_cruise_buttons(self, CS, self.CP.openpilotLongitudinalControl) # decrease the soft disable timer at every step, as it's reset on # entrance in SOFT_DISABLING state self.soft_disable_timer = max(0, self.soft_disable_timer - 1) self.current_alert_types = [ET.PERMANENT] # ENABLED, PRE ENABLING, SOFT DISABLING if self.state != State.disabled: # user and immediate disable always have priority in a non-disabled state if self.events.any(ET.USER_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.USER_DISABLE) elif self.events.any(ET.IMMEDIATE_DISABLE): self.state = State.disabled self.current_alert_types.append(ET.IMMEDIATE_DISABLE) else: # ENABLED if self.state == State.enabled: if self.events.any(ET.SOFT_DISABLE): self.state = State.softDisabling self.soft_disable_timer = 50 # 0.5s self.current_alert_types.append(ET.SOFT_DISABLE) # SOFT DISABLING elif self.state == State.softDisabling: if not self.events.any(ET.SOFT_DISABLE): # no more soft disabling condition, so go back to ENABLED self.state = State.enabled elif self.events.any(ET.SOFT_DISABLE) and self.soft_disable_timer > 0: self.current_alert_types.append(ET.SOFT_DISABLE) elif self.soft_disable_timer <= 0: self.state = State.disabled # PRE ENABLING elif self.state == State.preEnabled: if not self.events.any(ET.PRE_ENABLE): self.state = State.enabled else: self.current_alert_types.append(ET.PRE_ENABLE) # DISABLED elif self.state == State.disabled: if self.events.any(ET.ENABLE): if self.events.any(ET.NO_ENTRY): self.current_alert_types.append(ET.NO_ENTRY) else: if self.events.any(ET.PRE_ENABLE): self.state = State.preEnabled else: self.state = State.enabled self.current_alert_types.append(ET.ENABLE) self.v_cruise_kph = initialize_v_cruise(CS.vEgo, CS.buttonEvents, self.v_cruise_kph_last) # Check if actuators are enabled self.active = self.state == State.enabled or self.state == State.softDisabling if self.active: self.current_alert_types.append(ET.WARNING) # Check if openpilot is engaged self.enabled = self.active or self.state == State.preEnabled def state_control(self, CS): """Given the state, this function returns an actuators packet""" # Update VehicleModel params = self.sm['liveParameters'] x = max(params.stiffnessFactor, 0.1) #sr = max(params.steerRatio, 0.1) if ntune_isEnabled('useLiveSteerRatio'): sr = max(self.sm['liveParameters'].steerRatio, 0.1) else: if self.CP.carName in [CAR.GENESIS_G80]: sr = interp(abs(self.angle_steers_des), [5., 15.], [13., 17.]) else: sr = max(ntune_get('steerRatio'), 0.1) self.VM.update_params(x, sr) lat_plan = self.sm['lateralPlan'] long_plan = self.sm['longitudinalPlan'] actuators = car.CarControl.Actuators.new_message() if CS.leftBlinker or CS.rightBlinker: self.last_blinker_frame = self.sm.frame # State specific actions if not self.active: self.LaC.reset() self.LoC.reset(v_pid=CS.vEgo) long_plan_age = DT_CTRL * (self.sm.frame - self.sm.rcv_frame['longitudinalPlan']) # no greater than dt mpc + dt, to prevent too high extraps dt = min(long_plan_age, LON_MPC_STEP + DT_CTRL) + DT_CTRL a_acc_sol = long_plan.aStart + (dt / LON_MPC_STEP) * (long_plan.aTarget - long_plan.aStart) v_acc_sol = long_plan.vStart + dt * (a_acc_sol + long_plan.aStart) / 2.0 # Gas/Brake PID loop #actuators.gas, actuators.brake = self.LoC.update(self.active, CS, v_acc_sol, long_plan.vTargetFuture, a_acc_sol, self.CP) # scc smoother actuators.gas, actuators.brake = self.LoC.update(self.active and CS.cruiseState.speed > 1., CS, v_acc_sol, long_plan.vTargetFuture, a_acc_sol, self.CP, self.sm['radarState']) # Steering PID loop and lateral MPC actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(self.active, CS, self.CP, self.VM, params, lat_plan) # Check for difference between desired angle and angle for angle based control angle_control_saturated = self.CP.steerControlType == car.CarParams.SteerControlType.angle and \ abs(actuators.steeringAngleDeg - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD if angle_control_saturated and not CS.steeringPressed and self.active: self.saturated_count += 1 else: self.saturated_count = 0 # Send a "steering required alert" if saturation count has reached the limit if (lac_log.saturated and not CS.steeringPressed) or \ (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): if len(lat_plan.dPathPoints): # Check if we deviated from the path left_deviation = actuators.steer > 0 and lat_plan.dPathPoints[0] < -0.1 right_deviation = actuators.steer < 0 and lat_plan.dPathPoints[0] > 0.1 #if left_deviation or right_deviation: # self.events.add(EventName.steerSaturated) return actuators, v_acc_sol, a_acc_sol, lac_log def publish_logs(self, CS, start_time, actuators, v_acc, a_acc, lac_log): """Send actuators and hud commands to the car, send controlsstate and MPC logging""" CC = car.CarControl.new_message() CC.enabled = self.enabled CC.actuators = actuators CC.cruiseControl.override = True CC.cruiseControl.cancel = self.CP.enableCruise and not self.enabled and CS.cruiseState.enabled # Some override values for Honda # brake discount removes a sharp nonlinearity brake_discount = (1.0 - clip(actuators.brake * 3., 0.0, 1.0)) speed_override = max(0.0, (self.LoC.v_pid + CS.cruiseState.speedOffset) * brake_discount) CC.cruiseControl.speedOverride = float(speed_override if self.CP.enableCruise else 0.0) CC.cruiseControl.accelOverride = self.CI.calc_accel_override(CS.aEgo, self.sm['longitudinalPlan'].aTarget, CS.vEgo, self.sm['longitudinalPlan'].vTarget) CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = self.enabled CC.hudControl.lanesVisible = self.enabled CC.hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 CC.hudControl.rightLaneVisible = bool(right_lane_visible) CC.hudControl.leftLaneVisible = bool(left_lane_visible) recent_blinker = (self.sm.frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ and not self.active and self.sm['liveCalibration'].calStatus == Calibration.CALIBRATED meta = self.sm['modelV2'].meta if len(meta.desirePrediction) and ldw_allowed: l_lane_change_prob = meta.desirePrediction[Desire.laneChangeLeft - 1] r_lane_change_prob = meta.desirePrediction[Desire.laneChangeRight - 1] cameraOffset = ntune_get("cameraOffset") l_lane_close = left_lane_visible and (self.sm['modelV2'].laneLines[1].y[0] > -(1.08 + cameraOffset)) r_lane_close = right_lane_visible and (self.sm['modelV2'].laneLines[2].y[0] < (1.08 - cameraOffset)) CC.hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) CC.hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) if CC.hudControl.rightLaneDepart or CC.hudControl.leftLaneDepart: self.events.add(EventName.ldw) clear_event = ET.WARNING if ET.WARNING not in self.current_alert_types else None alerts = self.events.create_alerts(self.current_alert_types, [self.CP, self.sm, self.is_metric]) self.AM.add_many(self.sm.frame, alerts, self.enabled) self.AM.process_alerts(self.sm.frame, clear_event) CC.hudControl.visualAlert = self.AM.visual_alert if not self.read_only: # send car controls over can can_sends = self.CI.apply(CC, self) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) # Curvature & Steering angle params = self.sm['liveParameters'] lat_plan = self.sm['lateralPlan'] steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetAverageDeg) curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo) self.angle_steers_des = math.degrees(self.VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) self.angle_steers_des += params.angleOffsetDeg # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid controlsState = dat.controlsState controlsState.alertText1 = self.AM.alert_text_1 controlsState.alertText2 = self.AM.alert_text_2 controlsState.alertSize = self.AM.alert_size controlsState.alertStatus = self.AM.alert_status controlsState.alertBlinkingRate = self.AM.alert_rate controlsState.alertType = self.AM.alert_type controlsState.alertSound = self.AM.audible_alert controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.curvature = curvature controlsState.steeringAngleDesiredDeg = self.angle_steers_des controlsState.state = self.state controlsState.engageable = not self.events.any(ET.NO_ENTRY) controlsState.longControlState = self.LoC.long_control_state controlsState.vPid = float(self.LoC.v_pid) controlsState.vCruise = float(self.cruiseVirtualMaxSpeed if self.CP.openpilotLongitudinalControl else self.v_cruise_kph) controlsState.upAccelCmd = float(self.LoC.pid.p) controlsState.uiAccelCmd = float(self.LoC.pid.i) controlsState.ufAccelCmd = float(self.LoC.pid.f) controlsState.vTargetLead = float(v_acc) controlsState.aTarget = float(a_acc) controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_error_counter controlsState.angleSteers = steer_angle_without_offset * CV.RAD_TO_DEG controlsState.cluSpeedMs = self.clu_speed_ms controlsState.applyAccel = self.apply_accel controlsState.fusedAccel = self.fused_accel controlsState.leadDist = self.lead_drel controlsState.aReqValue = self.aReqValue controlsState.aReqValueMin = self.aReqValueMin controlsState.aReqValueMax = self.aReqValueMax controlsState.steerRatio = self.VM.sR controlsState.steerRateCost = ntune_get('steerRateCost') controlsState.steerActuatorDelay = ntune_get('steerActuatorDelay') if self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log elif self.CP.lateralTuning.which() == 'pid': controlsState.lateralControlState.pidState = lac_log elif self.CP.lateralTuning.which() == 'lqr': controlsState.lateralControlState.lqrState = lac_log elif self.CP.lateralTuning.which() == 'indi': controlsState.lateralControlState.indiState = lac_log self.pm.send('controlsState', dat) # carState car_events = self.events.to_msg() cs_send = messaging.new_message('carState') cs_send.valid = CS.canValid cs_send.carState = CS cs_send.carState.events = car_events self.pm.send('carState', cs_send) # carEvents - logged every second or on change if (self.sm.frame % int(1. / DT_CTRL) == 0) or (self.events.names != self.events_prev): ce_send = messaging.new_message('carEvents', len(self.events)) ce_send.carEvents = car_events self.pm.send('carEvents', ce_send) self.events_prev = self.events.names.copy() # carParams - logged every 50 seconds (> 1 per segment) if (self.sm.frame % int(50. / DT_CTRL) == 0): cp_send = messaging.new_message('carParams') cp_send.carParams = self.CP self.pm.send('carParams', cp_send) # carControl cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid cc_send.carControl = CC self.pm.send('carControl', cc_send) # copy CarControl to pass to CarInterface on the next iteration self.CC = CC def step(self): start_time = sec_since_boot() self.prof.checkpoint("Ratekeeper", ignore=True) # Sample data from sockets and get a carState CS = self.data_sample() self.prof.checkpoint("Sample") self.update_events(CS) if not self.read_only: # Update control state self.state_transition(CS) self.prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_acc, a_acc, lac_log = self.state_control(CS) self.prof.checkpoint("State Control") # Publish data self.publish_logs(CS, start_time, actuators, v_acc, a_acc, lac_log) self.prof.checkpoint("Sent") def controlsd_thread(self): while True: self.step() self.rk.monitor_time() self.prof.display()