class Controls: def __init__(self, sm=None, pm=None, can_sock=None, CI=None): config_realtime_process(4, Priority.CTRL_HIGH) # Ensure the current branch is cached, otherwise the first iteration of controlsd lags self.branch = get_short_branch("") # 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", "wideRoadCameraState" ] self.can_sock = can_sock if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 20 self.can_sock = messaging.sub_sock('can', timeout=can_timeout) 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 = [] if SIMULATION: ignore += ['driverCameraState', 'managerState'] if params.get_bool('WideCameraOnly'): ignore += ['roadCameraState'] 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 if self.CP.dashcamOnly and params.get_bool("DashcamOverride"): self.CP.dashcamOnly = False # 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) self.LaC: LatControl 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() == 'torque': self.LaC = LatControlTorque(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 = V_CRUISE_INITIAL self.v_cruise_cluster_kph = V_CRUISE_INITIAL 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 = None self.button_timers = { ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0 } self.last_actuators = car.CarControl.Actuators.new_message() self.steer_limited = False self.desired_curvature = 0.0 self.desired_curvature_rate = 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, 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 set_initial_state(self): if REPLAY: controls_state = Params().get("ReplayControlsState") if controls_state is not None: controls_state = log.ControlsState.from_bytes(controls_state) self.v_cruise_kph = controls_state.vCruise if self.sm['pandaStates'][0].controlsAllowed: self.state = State.enabled 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 # Block resume if cruise never previously enabled resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) if not self.CP.pcmCruise and self.v_cruise_kph == V_CRUISE_INITIAL and resume_pressed: self.events.add(EventName.resumeBlocked) # 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) if not self.CP.notCar: self.events.add_from_msg(self.sm['driverMonitoringState'].events) # Add car events, ignore if CAN isn't valid if CS.canValid: self.events.add_from_msg(CS.events) # Create events for temperature, disk space, and memory 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 and not SIMULATION: self.events.add(EventName.lowMemory) # TODO: enable this once loggerd CPU usage is more reasonable #cpus = list(self.sm['deviceState'].cpuUsagePercent) #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 == 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) 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) # Handle HW and system malfunctions # Order is very intentional here. Be careful when modifying this. # All events here should at least have NO_ENTRY and SOFT_DISABLE. num_events = len(self.events) not_running = { p.name for p in self.sm['managerState'].processes if not p.running and p.shouldBeRunning } if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) else: if not SIMULATION and not self.rk.lagging: 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.rk.lagging: self.events.add(EventName.controlsdLagging) if len(self.sm['radarState'].radarErrors) or not self.sm.all_checks( ['radarState']): self.events.add(EventName.radarFault) if not self.sm.valid['pandaStates']: self.events.add(EventName.usbError) if CS.canTimeout: self.events.add(EventName.canBusMissing) elif not CS.canValid: self.events.add(EventName.canError) # generic catch-all. ideally, a more specific event should be added above instead has_disable_events = self.events.any(ET.NO_ENTRY) and (self.events.any( ET.SOFT_DISABLE) or self.events.any(ET.IMMEDIATE_DISABLE)) no_system_errors = (not has_disable_events) or (len(self.events) == num_events) if (not self.sm.all_checks() or self.can_rcv_error) and no_system_errors: 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) logs = { '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], 'can_error': self.can_rcv_error, } if logs != self.logged_comm_issue: cloudlog.event("commIssue", error=True, **logs) self.logged_comm_issue = logs else: self.logged_comm_issue = None 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['liveParameters'].sensorValid or 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(6. / 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) 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 self.sm['modelV2'].frameDropPerc > 20: self.events.add(EventName.modeldLagging) if self.sm['liveLocationKalman'].excessiveResets: self.events.add(EventName.localizerMalfunction) # 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() timed_out = self.sm.frame * DT_CTRL > (6. if REPLAY else 3.5) if all_valid or timed_out or SIMULATION: if not self.read_only: self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) self.initialized = True self.set_initial_state() 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 CS.cruiseState.available: # 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.vEgo, CS.gasPressed, CS.buttonEvents, self.button_timers, self.enabled, self.is_metric) self.v_cruise_cluster_kph = self.v_cruise_kph else: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH else: self.v_cruise_kph = V_CRUISE_INITIAL self.v_cruise_cluster_kph = V_CRUISE_INITIAL # 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) self.v_cruise_cluster_kph = self.v_cruise_kph # 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) and self.CP.openpilotLongitudinalControl 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, long_plan, pid_accel_limits, t_since_plan) # Steering PID loop and lateral MPC self.desired_curvature, self.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.VM, params, self.last_actuators, self.steer_limited, self.desired_curvature, self.desired_curvature_rate, self.sm['liveLocationKalman']) 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 not CS.steeringPressed and self.CP.lateralTuning.which( ) == 'torque' and not self.joystick_mode: undershooting = abs(lac_log.desiredLateralAccel) / abs( 1e-3 + lac_log.actualLateralAccel) > 1.2 turning = abs(lac_log.desiredLateralAccel) > 1.0 good_speed = CS.vEgo > 5 max_torque = abs(self.last_actuators.steer) > 0.99 if undershooting and turning and good_speed and max_torque: self.events.add(EventName.steerSaturated) elif lac_log.active and not CS.steeringPressed and lac_log.saturated: dpath_points = lat_plan.dPathPoints if len(dpath_points): # Check if we deviated from the path # TODO use desired vs actual curvature if self.CP.steerControlType == car.CarParams.SteerControlType.angle: steering_value = actuators.steeringAngleDeg else: steering_value = actuators.steer left_deviation = steering_value > 0 and dpath_points[0] < -0.20 right_deviation = steering_value < 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, SupportsFloat): 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 speeds = self.sm['longitudinalPlan'].speeds if len(speeds): CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[ -1] > 0.1 hudControl = CC.hudControl hudControl.setSpeed = float(self.v_cruise_cluster_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, CS, 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 self.steer_limited = abs(CC.actuators.steer - CC.actuatorsOutput.steer) > 1e-2 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.desiredCurvature = self.desired_curvature controlsState.desiredCurvatureRate = self.desired_curvature_rate 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.vCruiseCluster = float(self.v_cruise_cluster_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 == 'torque': controlsState.lateralControlState.torqueState = 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()
def controlsd_thread(gctx=None, rate=100, default_bias=0.): gc.disable() # start the loop set_realtime_priority(3) context = zmq.Context() params = Params() # pub live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) livempc = messaging.pub_sock(context, service_list['liveMpc'].port) is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" if not passive: while 1: try: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) break except zmq.error.ZMQError: kill_defaultd() else: sendcan = None # sub poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) gps_location = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) if CI is None: raise Exception("unsupported car") # if stock camera is connected, then force passive behavior if not CP.enableCamera: passive = True sendcan = None if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput fcw_enabled = params.get("IsFcwEnabled") == "1" geofence = None PL = Planner(CP, fcw_enabled) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(VM) AM = AlertManager() driver_status = DriverStatus() if not passive: AM.add("startup", False) # write CarParams params.put("CarParams", CP.to_bytes()) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) # learned angle offset angle_offset = default_bias calibration_params = params.get("CalibrationParams") if calibration_params: try: calibration_params = json.loads(calibration_params) angle_offset = calibration_params["angle_offset2"] except (ValueError, KeyError): pass prof = Profiler(False) # off by default # Setup for real-time tuning rt_tuning_file = '/data/.openpilot_rtt_params.pkl' rtt_params = {} last_mod_time = 0 while 1: prof.checkpoint("Ratekeeper", ignore=True) # sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter = data_sample( CI, CC, thermal, cal, health, driver_monitor, gps_location, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, geofence, state, mismatch_counter, params) prof.checkpoint("Sample") # define plan plan, plan_ts = calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence) prof.checkpoint("Plan") if not passive: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # compute actuators actuators, v_cruise_kph, driver_status, angle_offset = state_control( plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc) prof.checkpoint("State Control") # publish data CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive) prof.checkpoint("Sent") ###################### Real-Time Tuning Add-on ######################## # TODO: Move this into it's own function to clean things up # TODO: Need to delay until fingerprint, or is this after already? # Run this once per second... on frame 29, of course. if rk.frame % 100 == 29: # Get the last update time of our real-time tuning file #print('Real-Time Tuning: Checking tuning file modification time.') try: mod_time = os.path.getmtime(rt_tuning_file) #print('RTT mod_time: {0}'.format(mod_time)) except OSError: # File doesn't exist or is inaccessible mod_time = None print( 'Real-Time Tuning: RT_TUNING_FILE did not exist or was inaccessible.' ) # If rt_tuning_file doesn't exist, then create it from the current CarParams: if mod_time is None: rtt_params['steerKpBP'] = list( CP.steerKpBP ) # Note that the Kp/Ki are lists! But if you reference them directly they are <capnp list builder []>.. oops. rtt_params['steerKpV'] = list(CP.steerKpV) rtt_params['steerKiBP'] = list(CP.steerKiBP) rtt_params['steerKiV'] = list(CP.steerKiV) rtt_params['steerKf'] = CP.steerKf # TODO: Give the option to link the front and rear tire stiffness changes together rtt_params['tireStiffnessFront'] = CP.tireStiffnessFront rtt_params['tireStiffnessRear'] = CP.tireStiffnessRear rtt_params['steerRatio'] = CP.steerRatio rtt_params['steerRateCost'] = CP.steerRateCost rtt_params['latPidDeadzone'] = 0.0 rtt_params['steerActuatorDelay'] = CP.steerActuatorDelay # rtt_params['Camera Offset'] = PL.PP.cam_offset # Write the pickle file # TODO: try/except the open with open(rt_tuning_file, "wb") as f_write: pickle.dump( rtt_params, f_write, -1) # Dump to file with highest protocol (fastest) # No need to update next time if we just wrote the file out... last_mod_time = os.path.getmtime(rt_tuning_file) #print('RTT Last_mod_time: {0}'.format(last_mod_time)) # If file exists and has been updated since the last time we read it in elif last_mod_time != mod_time: print( 'Real-Time Tuning: Reading in the modified tuning file.') # Read in parameters from file # TODO: try/except the open with open(rt_tuning_file, "rb") as f_read: rtt_params = pickle.load(f_read) # Sanity check the data before setting it.. format is [min, max, failsafe] # Failsafe is used if a value is not found or if the value sent is out of the range limits rt_data_limits = { 'steerKpBP': [0.0, 67.0, 0.0], 'steerKpV': [0.0, 1.0, 0.2], 'steerKiBP': [0.0, 67.0, 0.0], 'steerKiV': [0.0, 1.0, 0.05], 'steerKf': [0.0, 0.001, 0.00005], 'tireStiffnessFront': [20000, 1000000, 192150], 'tireStiffnessRear': [20000, 1000000, 202500], 'steerRatio': [8.0, 25.0, 14.0], 'steerRateCost': [0.05, 1.0, 0.5], 'latPidDeadzone': [0.0, 4.0, 0.0], 'steerActuatorDelay': [0.0, 0.5, 0.1] # 'Camera Offset': [ -0.2, 0.2, 0.06 ] } # Do the checks and set the values for key in rt_data_limits: rt_val = rtt_params.get(key) if rt_val is None: # If this key from data limits doesn't exist in our tuning data, then add it as the failsafe # TODO: Use CP value here instead of failsafe? rtt_params[key] = rt_data_limits[key][2] print( 'Real-Time Tuning: Value did not exist in tuning file, replaced with failsafe. Key: ' + key) continue # If it does exist, then check the values. First see if it's a list try: # If it's an iterable list... for i, val2 in enumerate(rt_val): # Check each value in the list if (val2 < rt_data_limits[key][0]) or ( val2 > rt_data_limits[key][1]): rt_val[i] = rt_data_limits[key][2] print( 'Real-Time Tuning: Invalid value replaced! Key: ' + key) except: # Not interable, compare it and fix if necessary if (rt_val < rt_data_limits[key][0]) or ( rt_val > rt_data_limits[key][1]): rt_val = rt_data_limits[key][2] print( 'Real-Time Tuning: Invalid value replaced! Key: ' + key) # Set it back so if anything was fixed we have the updated value rtt_params[key] = rt_val # Update CP with the new params CP.steerKpBP = rtt_params['steerKpBP'] CP.steerKpV = rtt_params['steerKpV'] CP.steerKiBP = rtt_params['steerKiBP'] CP.steerKiV = rtt_params['steerKiV'] CP.steerKf = rtt_params['steerKf'] CP.tireStiffnessFront = rtt_params['tireStiffnessFront'] CP.tireStiffnessRear = rtt_params['tireStiffnessRear'] CP.steerRatio = rtt_params['steerRatio'] CP.steerActuatorDelay = rtt_params['steerActuatorDelay'] if CP.steerRateCost != rtt_params['steerRateCost']: print(CP.steerRateCost) print(rtt_params['steerRateCost']) CP.steerRateCost = rtt_params['steerRateCost'] rt_mpc_flag = True print( 'Real-Time Tuning: CP.steerRateCost changed - Re-initializing lateral MPC.' ) else: rt_mpc_flag = False # TODO: try/except the open # Write the pickle file back so if we fixed any data errors the revised values will show up on the client-side with open(rt_tuning_file, "wb") as f_write: pickle.dump( rtt_params, f_write, -1) # Dump to file with highest protocol (fastest) # Set the last modified time to this write.... we don't need to read back in what we just wrote out # Only set this if we were able to successfully make the write (once the try/except is added) last_mod_time = os.path.getmtime(rt_tuning_file) # Make updates in latcontrol, etc. I'm not sure if this is actually necessary, depends on if the objects are referenced or not. Anyway, one less thing to debug atm. VM.update_rt_params(CP) LaC.update_rt_params(VM, rt_mpc_flag, deadzone=rtt_params['latPidDeadzone']) #PL.PP.update_rt_params(rtt_params['Camera Offset']) #print('RTT Last_mod_time: {0}'.format(last_mod_time)) ####### END OF REAL-TIME TUNING ADD-ON ####### # *** run loop at fixed rate *** rk.keep_time() 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.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, ignore_avg_freq=['radarState']) 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 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 params = Params() self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") self.enable_lte_onroad = params.get_bool("EnableLteOnroad") 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' fuzzy_fingerprint = self.CP.fuzzyFingerprint # 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 = self.CP.communityFeature or fuzzy_fingerprint 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 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 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, fuzzy_fingerprint) 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) 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: 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 or self.enable_lte_onroad): # 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 if not self.CP.enableCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.enabled) elif self.CP.enableCruise 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) 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) # 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 = not self.CP.enableCruise or (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] 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: # 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'] 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) angle_steers_des = math.degrees(self.VM.get_steer_from_curvature(-lat_plan.curvature, CS.vEgo)) 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 = 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.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 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()
def controlsd_thread(sm=None, pm=None, can_sock=None): gc.disable() # start the loop set_realtime_priority(3) params = Params() is_metric = params.get("IsMetric", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = passive or not openpilot_enabled_toggle # Pub/Sub Sockets if pm is None: pm = messaging.PubMaster(['sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams']) if sm is None: sm = messaging.SubMaster(['thermal', 'health', 'liveCalibration', 'driverMonitoring', 'plan', 'pathPlan', \ 'gpsLocation'], ignore_alive=['gpsLocation']) can_poller = zmq.Poller() if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 can_sock = messaging.sub_sock(service_list['can'].port, timeout=can_timeout) can_poller.register(can_sock) # wait for health and CAN packets hw_type = messaging.recv_one(sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno] print("Waiting for CAN messages...") get_one_can(can_sock) CI, CP = get_car(can_sock, pm.sock['sendcan'], has_relay) car_recognized = CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not chffrplus controller_available = CP.enableCamera and CI.CC is not None and not passive read_only = not car_recognized or not controller_available or CP.dashcamOnly if read_only: CP.safetyModel = CP.safetyModelPassive # Write CarParams for radard and boardd safety mode params.put("CarParams", CP.to_bytes()) params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") CC = car.CarControl.new_message() AM = AlertManager() startup_alert = get_startup_alert(car_recognized, controller_available) AM.add(sm.frame, startup_alert, False) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) if CP.lateralTuning.which() == 'pid': LaC = LatControlPID(CP) elif CP.lateralTuning.which() == 'indi': LaC = LatControlINDI(CP) elif CP.lateralTuning.which() == 'lqr': LaC = LatControlLQR(CP) driver_status = DriverStatus() is_rhd = params.get("IsRHD") if is_rhd is not None: driver_status.is_rhd = bool(int(is_rhd)) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False events_prev = [] sm['pathPlan'].sensorValid = True sm['pathPlan'].posenetValid = True # detect sound card presence sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0') and open('/proc/asound/card0/state').read().strip() == 'ONLINE') # controlsd is driven by can recv, expected at 100Hz rk = Ratekeeper(100, print_delay_threshold=None) # FIXME: offroad alerts should not be created with negative severity connectivity_alert = params.get("Offroad_ConnectivityNeeded", encoding='utf8') internet_needed = connectivity_alert is not None and json.loads(connectivity_alert.replace("'", "\""))["severity"] >= 0 prof = Profiler(False) # off by default while True: start_time = sec_since_boot() prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter =\ data_sample(CI, CC, sm, can_poller, can_sock, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, state, mismatch_counter, params) prof.checkpoint("Sample") # Create alerts if not sm.all_alive_and_valid(): events.append(create_event('commIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not sm['pathPlan'].mpcSolutionValid: events.append(create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not sm['pathPlan'].sensorValid: events.append(create_event('sensorDataInvalid', [ET.NO_ENTRY, ET.PERMANENT])) if not sm['pathPlan'].paramsValid: events.append(create_event('vehicleModelInvalid', [ET.WARNING])) if not sm['pathPlan'].posenetValid: events.append(create_event('posenetInvalid', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not sm['plan'].radarValid: events.append(create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if sm['plan'].radarCanError: events.append(create_event('radarCanError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not CS.canValid: events.append(create_event('canError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not sounds_available: events.append(create_event('soundsUnavailable', [ET.NO_ENTRY, ET.PERMANENT])) if internet_needed: events.append(create_event('internetConnectivityNeeded', [ET.NO_ENTRY, ET.PERMANENT])) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not read_only: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(sm.frame, CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, driver_status, v_acc, a_acc, lac_log = \ state_control(sm.frame, sm.rcv_frame, sm['plan'], sm['pathPlan'], CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, LaC, LoC, read_only, is_metric, cal_perc) prof.checkpoint("State Control") # Publish data CC, events_prev = data_send(sm, pm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, AM, driver_status, LaC, LoC, read_only, start_time, v_acc, a_acc, lac_log, events_prev) prof.checkpoint("Sent") rk.monitor_time() prof.display()
def controlsd_thread(gctx=None, rate=100): gc.disable() # start the loop set_realtime_priority(3) context = zmq.Context() params = Params() # Pub Sockets live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" # No sendcan if passive if not passive: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) else: sendcan = None # Sub sockets poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) plan_sock = messaging.sub_sock(context, service_list['plan'].port, conflate=True, poller=poller) path_plan_sock = messaging.sub_sock(context, service_list['pathPlan'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) if CI is None: raise Exception("unsupported car") # if stock camera is connected, then force passive behavior if not CP.enableCamera: passive = True sendcan = None if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(CP) AM = AlertManager() driver_status = DriverStatus() if not passive: AM.add("startup", False) # Write CarParams for radard and boardd safety mode params.put("CarParams", CP.to_bytes()) params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False plan = messaging.new_message() plan.init('plan') path_plan = messaging.new_message() path_plan.init('pathPlan') rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) controls_params = params.get("ControlsParams") # Read angle offset from previous drive angle_model_bias = 0. if controls_params is not None: try: controls_params = json.loads(controls_params) angle_model_bias = controls_params['angle_model_bias'] except (ValueError, KeyError): pass prof = Profiler(False) # off by default while True: start_time = int(sec_since_boot() * 1e9) prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter, plan, path_plan =\ data_sample(CI, CC, plan_sock, path_plan_sock, thermal, cal, health, driver_monitor, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, state, mismatch_counter, params, plan, path_plan) prof.checkpoint("Sample") path_plan_age = (start_time - path_plan.logMonoTime) / 1e9 plan_age = (start_time - plan.logMonoTime) / 1e9 if not path_plan.pathPlan.valid or plan_age > 0.5 or path_plan_age > 0.5: events.append( create_event('plannerError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not path_plan.pathPlan.paramsValid: events.append(create_event('vehicleModelInvalid', [ET.WARNING])) events += list(plan.plan.events) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and plan.plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: events.append( create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not passive: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc, a_acc = \ state_control(plan.plan, path_plan.pathPlan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, LaC, LoC, VM, angle_model_bias, passive, is_metric, cal_perc) prof.checkpoint("State Control") # Publish data CC = data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, AM, driver_status, LaC, LoC, angle_model_bias, passive, start_time, params, v_acc, a_acc) prof.checkpoint("Sent") rk.keep_time() # Run at 100Hz prof.display()
def __init__(self, gctx, rate=100): self.rate = rate # *** log *** context = zmq.Context() # pub self.live100 = messaging.pub_sock(context, service_list['live100'].port) self.carstate = messaging.pub_sock(context, service_list['carState'].port) self.carcontrol = messaging.pub_sock(context, service_list['carControl'].port) sendcan = messaging.pub_sock(context, service_list['sendcan'].port) # sub self.thermal = messaging.sub_sock(context, service_list['thermal'].port) self.health = messaging.sub_sock(context, service_list['health'].port) logcan = messaging.sub_sock(context, service_list['can'].port) self.cal = messaging.sub_sock(context, service_list['liveCalibration'].port) self.CC = car.CarControl.new_message() self.CI, self.CP = get_car(logcan, sendcan) self.PL = Planner(self.CP) self.AM = AlertManager() self.LoC = LongControl() self.LaC = LatControl() # write CarParams params = Params() params.put("CarParams", self.CP.to_bytes()) # fake plan self.plan_ts = 0 self.plan = log.Plan.new_message() self.plan.lateralValid = False self.plan.longitudinalValid = False # controls enabled state self.enabled = False self.last_enable_request = 0 # learned angle offset self.angle_offset = 0 # rear view camera state self.rear_view_toggle = False self.rear_view_allowed = bool(params.get("IsRearViewMirror")) self.v_cruise_kph = 255 # 0.0 - 1.0 self.awareness_status = 1.0 self.soft_disable_timer = None self.overtemp = False self.free_space = 1.0 self.cal_status = Calibration.UNCALIBRATED self.cal_perc = 0 self.rk = Ratekeeper(self.rate, print_delay_threshold=2. / 1000)
def __init__(self, sm=None, pm=None, can_sock=None, arne_sm=None): gc.disable() set_realtime_priority(53) set_core_affinity(3) # 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: self.sm = messaging.SubMaster(['thermal', 'health', 'frame', 'model', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman', 'radarState']) self.arne_sm = arne_sm if self.arne_sm is None: self.arne_sm = messaging_arne.SubMaster(['arne182Status', 'dynamicFollowButton', 'trafficModelEvent', 'modelLongButton' ]) self.op_params = opParams() self.df_manager = dfManager(self.op_params) self.hide_auto_df_alerts = self.op_params.get('hide_auto_df_alerts') self.traffic_light_alerts = self.op_params.get('traffic_light_alerts') self.last_model_long = False 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 health and one CAN packet hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno, HwType.dos] print("Waiting for CAN messages...") messaging.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("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" internet_needed = (params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None) and (params.get("DisableUpdates") != b"1") community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init #sounds_available = not ANDROID or 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 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) put_nonblocking("LongitudinalControl", "1" if self.CP.openpilotLongitudinalControl else "0") if self.CP.openpilotLongitudinalControl and self.CP.safetyModel in [car.CarParams.SafetyModel.hondaBoschGiraffe, car.CarParams.SafetyModel.hondaBoschHarness]: disable_radar(can_sock, pm.sock['sendcan'], 1 if has_relay else 0, timeout=1, retry=10) self.CC = car.CarControl.new_message() self.AM = AlertManager() self.events = Events() self.eventsArne182 = Events_arne182() self.LoC = LongControl(self.CP, self.CI.compute_gb) self.VM = VehicleModel(self.CP) if 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.last_ldw_frame = 0 self.saturated_count = 0 self.distance_traveled_now = 0 if not travis: self.distance_traveled = float(params.get("DistanceTraveled", encoding='utf8')) self.distance_traveled_engaged = float(params.get("DistanceTraveledEngaged", encoding='utf8')) self.distance_traveled_override = float(params.get("DistanceTraveledOverride", encoding='utf8')) else: self.distance_traveled = 0 self.distance_traveled_engaged = 0 self.distance_traveled_override = 0 self.distance_traveled_frame = 0 self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.sm['liveCalibration'].calStatus = Calibration.INVALID self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False self.startup_event = get_startup_event(car_recognized, controller_available) #if not sounds_available: # self.events.add(EventName.soundsUnavailable, static=True) if internet_needed: self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if self.read_only and not passive: self.events.add(EventName.carUnrecognized, static=True) if hw_type == HwType.whitePanda: self.events.add(EventName.whitePandaUnsupported, 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 __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', 'pandaStates', 'peripheralState', '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: 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.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) elif self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP, self.CI) 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.cruise_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.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 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) 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 controlsd_thread(gctx, rate=100): # start the loop set_realtime_priority(3) context = zmq.Context() params = Params() # pub live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) livempc = messaging.pub_sock(context, service_list['liveMpc'].port) passive = params.get("Passive") != "0" if not passive: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) else: sendcan = None # sub poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) if CI is None: raise Exception("unsupported car") if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput fcw_enabled = params.get("IsFcwEnabled") == "1" PL = Planner(CP, fcw_enabled) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(VM) AM = AlertManager() if not passive: AM.add("startup", False) # write CarParams params.put("CarParams", CP.to_bytes()) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 overtemp = False free_space = False cal_status = Calibration.UNCALIBRATED rear_view_toggle = False rear_view_allowed = params.get("IsRearViewMirror") == "1" # 0.0 - 1.0 awareness_status = 1. v_cruise_kph_last = 0 rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) # learned angle offset angle_offset = 1.5 # Default model bias calibration_params = params.get("CalibrationParams") if calibration_params: try: calibration_params = json.loads(calibration_params) angle_offset = calibration_params["angle_offset"] except (ValueError, KeyError): pass prof = Profiler(False) # off by default while 1: prof.checkpoint("Ratekeeper", ignore=True) # rk is here # sample data and compute car events CS, events, cal_status, overtemp, free_space = data_sample( CI, CC, thermal, cal, health, poller, cal_status, overtemp, free_space) prof.checkpoint("Sample") # define plan plan, plan_ts = calc_plan(CS, events, PL, LoC, v_cruise_kph, awareness_status) prof.checkpoint("Plan") if not passive: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = state_transition( CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # compute actuators actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle = state_control( plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, awareness_status, PL, LaC, LoC, VM, angle_offset, rear_view_allowed, rear_view_toggle) prof.checkpoint("State Control") # publish data CC = data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, livempc, AM, rear_view_allowed, rear_view_toggle, awareness_status, LaC, LoC, angle_offset, passive) prof.checkpoint("Sent") # *** run loop at fixed rate *** rk.keep_time() prof.display()
def controlsd_thread(gctx=None): gc.disable() # start the loop set_realtime_priority(3) params = Params() # Pub Sockets sendcan = messaging.pub_sock(service_list['sendcan'].port) controlsstate = messaging.pub_sock(service_list['controlsState'].port) carstate = messaging.pub_sock(service_list['carState'].port) carcontrol = messaging.pub_sock(service_list['carControl'].port) carevents = messaging.pub_sock(service_list['carEvents'].port) carparams = messaging.pub_sock(service_list['carParams'].port) is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" sm = messaging.SubMaster([ 'thermal', 'health', 'liveCalibration', 'driverMonitoring', 'plan', 'pathPlan' ]) logcan = messaging.sub_sock(service_list['can'].port) # wait for health and CAN packets hw_type = messaging.recv_one(sm.sock['health']).health.hwType is_panda_black = hw_type == log.HealthData.HwType.blackPanda #wait_for_can(logcan) CI, CP = get_car(logcan, sendcan, is_panda_black) logcan.close() # TODO: Use the logcan socket from above, but that will currenly break the tests can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 can_sock = messaging.sub_sock(service_list['can'].port, timeout=can_timeout) car_recognized = CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not chffrplus controller_available = CP.enableCamera and CI.CC is not None and not passive read_only = not car_recognized or not controller_available if read_only: print 'IS READ-ONLY!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!' CP.safetyModel = car.CarParams.SafetyModel.elm327 # diagnostic only # Write CarParams for radard and boardd safety mode params.put("CarParams", CP.to_bytes()) params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") CC = car.CarControl.new_message() AM = AlertManager() startup_alert = get_startup_alert(car_recognized, controller_available) AM.add(sm.frame, startup_alert, False) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) if CP.lateralTuning.which() == 'pid': LaC = LatControlPID(CP) else: LaC = LatControlINDI(CP) driver_status = DriverStatus() state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False events_prev = [] sm['pathPlan'].sensorValid = True sm['pathPlan'].posenetValid = True # controlsd is driven by can recv, expected at 100Hz rk = Ratekeeper(100, print_delay_threshold=None) prof = Profiler(False) # off by default while True: start_time = sec_since_boot() prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter =\ data_sample(CI, CC, sm, can_sock, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, state, mismatch_counter, params) prof.checkpoint("Sample") # Create alerts if not sm.all_alive_and_valid(): events.append( create_event('commIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not sm['pathPlan'].mpcSolutionValid: events.append( create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not sm['pathPlan'].sensorValid: events.append( create_event('sensorDataInvalid', [ET.NO_ENTRY, ET.PERMANENT])) if not sm['pathPlan'].paramsValid: events.append(create_event('vehicleModelInvalid', [ET.WARNING])) if not sm['pathPlan'].posenetValid: events.append( create_event('posenetInvalid', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not sm['plan'].radarValid: events.append( create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if sm['plan'].radarCanError: events.append( create_event('radarCanError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not CS.canValid: events.append( create_event('canError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and sm[ 'plan'].vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: events.append( create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not read_only: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(sm.frame, CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, driver_status, v_acc, a_acc, lac_log = \ state_control(sm.frame, sm.rcv_frame, sm['plan'], sm['pathPlan'], CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, LaC, LoC, VM, read_only, is_metric, cal_perc) prof.checkpoint("State Control") # Publish data CC, events_prev = data_send(sm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, carevents, carparams, controlsstate, sendcan, AM, driver_status, LaC, LoC, read_only, start_time, v_acc, a_acc, lac_log, events_prev) prof.checkpoint("Sent") rk.monitor_time() prof.display()
def controlsd_thread(gctx=None): gc.disable() # start the loop set_realtime_priority(3) context = zmq.Context() params = Params() # Pub Sockets controlsstate = messaging.pub_sock(context, service_list['controlsState'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" sendcan = messaging.pub_sock(context, service_list['sendcan'].port) # Sub sockets poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) plan_sock = messaging.sub_sock(context, service_list['plan'].port, conflate=True, poller=poller) path_plan_sock = messaging.sub_sock(context, service_list['pathPlan'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan) AM = AlertManager() car_recognized = CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not chffrplus controller_available = CP.enableCamera and CI.CC is not None and not passive read_only = not car_recognized or not controller_available if read_only: CP.safetyModel = car.CarParams.SafetyModels.elm327 # diagnostic only startup_alert = get_startup_alert(car_recognized, controller_available) AM.add(startup_alert, False) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) if CP.lateralTuning.which() == 'pid': LaC = LatControlPID(CP) else: LaC = LatControlINDI(CP) driver_status = DriverStatus() # Write CarParams for radard and boardd safety mode params.put("CarParams", CP.to_bytes()) params.put("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False rcv_times = defaultdict(int) plan = messaging.new_message() plan.init('plan') path_plan = messaging.new_message() path_plan.init('pathPlan') path_plan.pathPlan.sensorValid = True # controlsd is driven by can recv, expected at 100Hz rk = Ratekeeper(100, print_delay_threshold=None) controls_params = params.get("ControlsParams") # Read angle offset from previous drive angle_model_bias = 0. if controls_params is not None: try: controls_params = json.loads(controls_params) angle_model_bias = controls_params['angle_model_bias'] except (ValueError, KeyError): pass prof = Profiler(False) # off by default while True: start_time = sec_since_boot() prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter, plan, path_plan =\ data_sample(rcv_times, CI, CC, plan_sock, path_plan_sock, thermal, cal, health, driver_monitor, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, state, mismatch_counter, params, plan, path_plan) prof.checkpoint("Sample") # Create alerts path_plan_age = start_time - rcv_times['pathPlan'] plan_age = start_time - rcv_times['plan'] if not path_plan.pathPlan.valid or plan_age > 0.5 or path_plan_age > 0.5: events.append( create_event('plannerError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not path_plan.pathPlan.sensorValid: events.append( create_event('sensorDataInvalid', [ET.NO_ENTRY, ET.PERMANENT])) if not path_plan.pathPlan.paramsValid: events.append(create_event('vehicleModelInvalid', [ET.WARNING])) if not path_plan.pathPlan.modelValid: events.append( create_event('modelCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not plan.plan.radarValid: events.append( create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if plan.plan.radarCommIssue: events.append( create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and plan.plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: events.append( create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not read_only: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, driver_status, angle_model_bias, v_acc, a_acc, lac_log = \ state_control(rcv_times, plan.plan, path_plan.pathPlan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, LaC, LoC, VM, angle_model_bias, read_only, is_metric, cal_perc) prof.checkpoint("State Control") # Publish data CC = data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, controlsstate, sendcan, AM, driver_status, LaC, LoC, angle_model_bias, read_only, start_time, v_acc, a_acc, lac_log) prof.checkpoint("Sent") rk.monitor_time() prof.display()
class Controls: def __init__(self, sm=None, pm=None, can_sock=None): config_realtime_process(3, Priority.CTRL_HIGH) self.op_params = opParams() # 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: self.sm = messaging.SubMaster([ 'thermal', 'health', 'model', 'liveCalibration', 'frontFrame', 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman', 'radarState', 'dynamicFollowData', 'liveTracks', 'dynamicFollowButton', 'modelLongButton' ]) self.op_params = opParams() self.df_manager = dfManager(self.op_params) self.hide_auto_df_alerts = self.op_params.get('hide_auto_df_alerts') self.support_white_panda = self.op_params.get('support_white_panda') self.last_model_long = False 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 health and one CAN packet print("Waiting for CAN messages...") get_one_can(self.can_sock) self.CI, self.CP, candidate = get_car(self.can_sock, self.pm.sock['sendcan']) threading.Thread(target=log_fingerprint, args=[candidate]).start() # read params params = Params() self.is_metric = params.get("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" internet_needed = (params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None) and ( params.get("DisableUpdates") != b"1") community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ internet_needed 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, candidate) self.VM = VehicleModel(self.CP) self.lateral_control_method = 0 if self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP) self.lateral_control_method = 0 elif self.CP.lateralTuning.which() == 'indi': self.LaC = LatControlINDI(self.CP) self.lateral_control_method = 1 elif self.CP.lateralTuning.which() == 'lqr': self.LaC = LatControlLQR(self.CP) self.lateral_control_method = 2 self.long_plan_source = 0 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.sm['liveCalibration'].calStatus = Calibration.CALIBRATED self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False self.startup_event = get_startup_event(car_recognized, controller_available) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) #if internet_needed: # self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, 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['dMonitoringState'].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['thermal'].batteryPercent < 1 and self.sm[ 'thermal'].chargingError: # at zero percent battery, while discharging, OP should not allowed self.events.add(EventName.lowBattery) if self.sm['thermal'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['thermal'].freeSpace < 0.07: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) if self.sm['thermal'].memUsedPercent > 90: self.events.add(EventName.lowMemory) # Alert if fan isn't spinning for 5 seconds if self.sm['health'].hwType in [HwType.uno, HwType.dos]: if self.sm['health'].fanSpeedRpm == 0 and self.sm[ 'thermal'].fanSpeed > 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[ 'pathPlan'].laneChangeState == LaneChangeState.preLaneChange: direction = self.sm['pathPlan'].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['pathPlan'].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) if (self.sm['health'].safetyModel != self.CP.safetyModel and self.sm.frame > 2 / DT_CTRL) or \ self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm.alive['plan'] and self.sm.alive['pathPlan']: # only plan not being received: radar not communicating self.events.add(EventName.radarCommIssue) elif not self.sm.all_alive_and_valid() and self.sm.frame > 5 / DT_CTRL: self.events.add(EventName.commIssue) if not self.sm['pathPlan'].mpcSolutionValid and not ( EventName.laneChangeManual in self.events.names) and CS.steeringAngle < 15: 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'].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 # if not (SIMULATION or NOSENSOR): # TODO: send GPS in carla # self.events.add(EventName.noGps) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['liveLocationKalman'].posenetOK: self.events.add(EventName.posenetInvalid) if not self.sm['liveLocationKalman'].deviceStable: self.events.add(EventName.deviceFalling) if not self.sm['plan'].radarValid: self.events.add(EventName.radarFault) if self.sm['plan'].radarCanError: self.events.add(EventName.radarCanError) if log.HealthData.FaultType.relayMalfunction in self.sm[ 'health'].faults: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: self.events.add(EventName.fcw) if not self.sm.alive['frontFrame'] and ( self.sm.frame > 5 / DT_CTRL) and not SIMULATION: self.events.add(EventName.cameraMalfunction) if self.sm['model'].frameDropPerc > 20 and not SIMULATION: self.events.add(EventName.modeldLagging) # Only allow engagement with brake pressed when stopped behind another stopped car #if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ # and self.CP.openpilotLongitudinalControl and CS.vEgo < 0.3: # self.events.add(EventName.noTarget) self.add_stock_additions_alerts(CS) def add_stock_additions_alerts(self, CS): self.AM.SA_set_frame(self.sm.frame) self.AM.SA_set_enabled(self.enabled) # alert priority is defined by code location, keeping is highest, then lane speed alert, then auto-df alert if self.sm['modelLongButton'].enabled != self.last_model_long: extra_text_1 = '비활성화!' if self.last_model_long else '활성화!' extra_text_2 = '' if self.last_model_long else ', 모델이 예기치 않게 작동할 수 있음' self.AM.SA_add('modelLongAlert', extra_text_1=extra_text_1, extra_text_2=extra_text_2) return df_out = self.df_manager.update() if df_out.changed: df_alert = 'dfButtonAlert' if df_out.is_auto and df_out.last_is_auto: # only show auto alert if engaged, not hiding auto, and time since lane speed alert not showing if CS.cruiseState.enabled and not self.hide_auto_df_alerts: df_alert += 'Silent' self.AM.SA_add(df_alert, extra_text_1=df_out.model_profile_text + ' (auto)') return else: self.AM.SA_add(df_alert, extra_text_1=df_out.user_profile_text, extra_text_2='동적차간거리조절: {} 프로파일 활성화됨'.format( df_out.user_profile_text)) return 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['health'].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.enableCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.vEgo, CS.gasPressed, 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 # 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""" plan = self.sm['plan'] path_plan = self.sm['pathPlan'] 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) plan_age = DT_CTRL * (self.sm.frame - self.sm.rcv_frame['plan']) # no greater than dt mpc + dt, to prevent too high extraps dt = min(plan_age, LON_MPC_STEP + DT_CTRL) + DT_CTRL a_acc_sol = plan.aStart + (dt / LON_MPC_STEP) * (plan.aTarget - plan.aStart) v_acc_sol = plan.vStart + dt * (a_acc_sol + plan.aStart) / 2.0 extras_loc = { 'lead_one': self.sm['radarState'].leadOne, 'mpc_TR': self.sm['dynamicFollowData'].mpcTR, 'live_tracks': self.sm['liveTracks'], 'has_lead': plan.hasLead } # Gas/Brake PID loop #actuators.gas, actuators.brake = self.LoC.update(self.active, CS, v_acc_sol, plan.vTargetFuture, a_acc_sol, self.CP, plan.hasLead, self.sm['radarState'], plan.decelForTurn, plan.longitudinalPlanSource, extras_loc) self.LoC.update(self.active, CS, v_acc_sol, plan.vTargetFuture, a_acc_sol, self.CP, plan.hasLead, self.sm['radarState'], plan.decelForTurn, plan.longitudinalPlanSource, extras_loc) actuators.gas = a_acc_sol if a_acc_sol > 0 else 0. actuators.brake = -a_acc_sol if a_acc_sol < 0 else 0. # Steering PID loop and lateral MPC actuators.steer, actuators.steerAngle, lac_log = self.LaC.update( self.active, CS, self.CP, path_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.steerAngle - CS.steeringAngle) > 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): # Check if we deviated from the path left_deviation = actuators.steer > 0 and path_plan.dPoly[3] > 0.1 right_deviation = actuators.steer < 0 and path_plan.dPoly[3] < -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""" self.log_alertTextMsg1 = trace1.global_alertTextMsg1 self.log_alertTextMsg2 = trace1.global_alertTextMsg2 CC = car.CarControl.new_message() CC.enabled = self.enabled CC.actuators = actuators CC.cruiseControl.override = True CC.cruiseControl.cancel = not self.CP.enableCruise or ( 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['plan'].aTarget, CS.vEgo, self.sm['plan'].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['plan'].hasLead CC.hudControl.leadDistance = 0 #self.sm['radarState'].leadOne.dRel CC.hudControl.leadvRel = 0 #self.sm['radarState'].leadOne.vRel CC.hudControl.leadyRel = 0 #self.sm['radarState'].leadOne.yRel right_lane_visible = self.sm['pathPlan'].rProb > 0.5 left_lane_visible = self.sm['pathPlan'].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['model'].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] if int(Params().get('OpkrLatMode')) == 3: l_lane_close = left_lane_visible and ( self.sm['pathPlan'].lPoly[3] < (1.08 - CAMERA_OFFSET_A)) r_lane_close = right_lane_visible and ( self.sm['pathPlan'].rPoly[3] > -(1.08 + CAMERA_OFFSET_A)) else: l_lane_close = left_lane_visible and ( self.sm['pathPlan'].lPoly[3] < (1.08 - CAMERA_OFFSET)) r_lane_close = right_lane_visible and ( self.sm['pathPlan'].rPoly[3] > -(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.last_model_long = self.sm['modelLongButton'].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.sm) self.pm.send( 'sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) force_decel = (self.sm['dMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) steer_angle_rad = (CS.steeringAngle - self.sm['pathPlan'].angleOffset) * CV.DEG_TO_RAD # 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.driverMonitoringOn = self.sm[ 'dMonitoringState'].faceDetected controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.planMonoTime = self.sm.logMonoTime['plan'] controlsState.pathPlanMonoTime = self.sm.logMonoTime['pathPlan'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.vEgo = CS.vEgo controlsState.vEgoRaw = CS.vEgoRaw controlsState.angleSteers = CS.steeringAngle controlsState.curvature = self.VM.calc_curvature( steer_angle_rad, CS.vEgo) controlsState.decelForTurn = self.sm['plan'].decelForTurn controlsState.steerOverride = CS.steeringPressed 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.id) controlsState.ufAccelCmd = float(self.LoC.pid.f) controlsState.angleSteersDes = float(self.LaC.angle_steers_des) controlsState.vTargetLead = float(v_acc) controlsState.aTarget = float(a_acc) controlsState.jerkFactor = float(self.sm['plan'].jerkFactor) controlsState.gpsPlannerActive = self.sm['plan'].gpsPlannerActive controlsState.vCurvature = self.sm['plan'].vCurvature controlsState.decelForModel = self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.model controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.mapValid = self.sm['plan'].mapValid controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_error_counter controlsState.alertTextMsg1 = self.log_alertTextMsg1 controlsState.alertTextMsg2 = self.log_alertTextMsg2 controlsState.lateralControlMethod = self.lateral_control_method if self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.cruise: self.long_plan_source = 1 elif self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.mpc1: self.long_plan_source = 2 elif self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.mpc2: self.long_plan_source = 3 elif self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.mpc3: self.long_plan_source = 4 elif self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.model: self.long_plan_source = 5 else: self.long_plan_source = 0 controlsState.longPlanSource = self.long_plan_source if 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()
def __init__(self, sm=None, pm=None, can_sock=None, CI=None): config_realtime_process(4, Priority.CTRL_HIGH) # Ensure the current branch is cached, otherwise the first iteration of controlsd lags self.branch = get_short_branch("") # 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", "wideRoadCameraState" ] self.can_sock = can_sock if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 20 self.can_sock = messaging.sub_sock('can', timeout=can_timeout) 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 = [] if SIMULATION: ignore += ['driverCameraState', 'managerState'] if params.get_bool('WideCameraOnly'): ignore += ['roadCameraState'] 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 if self.CP.dashcamOnly and params.get_bool("DashcamOverride"): self.CP.dashcamOnly = False # 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) self.LaC: LatControl 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() == 'torque': self.LaC = LatControlTorque(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 = V_CRUISE_INITIAL self.v_cruise_cluster_kph = V_CRUISE_INITIAL 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 = None self.button_timers = { ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0 } self.last_actuators = car.CarControl.Actuators.new_message() self.steer_limited = False self.desired_curvature = 0.0 self.desired_curvature_rate = 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, 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 controlsd_thread(gctx, rate=100): #rate in Hz # *** log *** context = zmq.Context() live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) thermal = messaging.sub_sock(context, service_list['thermal'].port) live20 = messaging.sub_sock(context, service_list['live20'].port) model = messaging.sub_sock(context, service_list['model'].port) health = messaging.sub_sock(context, service_list['health'].port) # connects to can and sendcan CI = CarInterface() VP = CI.getVehicleParams() PP = PathPlanner(model) AC = AdaptiveCruise(live20) AM = AlertManager() LoC = LongControl() LaC = LatControl() # controls enabled state enabled = False last_enable_request = 0 # learned angle offset angle_offset = 0 # rear view camera state rear_view_toggle = False v_cruise_kph = 255 # 0.0 - 1.0 awareness_status = 0.0 soft_disable_timer = None # Is cpu temp too high to enable? overtemp = False free_space = 1.0 # start the loop set_realtime_priority(2) rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) while 1: prof = Profiler() cur_time = sec_since_boot() # read CAN CS = CI.update() # broadcast carState cs_send = messaging.new_message() cs_send.init('carState') cs_send.carState = CS # copy? carstate.send(cs_send.to_bytes()) prof.checkpoint("CarInterface") # did it request to enable? enable_request, enable_condition = False, False if enabled: # gives the user 6 minutes awareness_status -= 1.0 / (100 * 60 * 6) if awareness_status <= 0.: AM.add("driverDistracted", enabled) # reset awareness status on steering if CS.steeringPressed: awareness_status = 1.0 # handle button presses for b in CS.buttonEvents: print b # reset awareness on any user action awareness_status = 1.0 # button presses for rear view if b.type == "leftBlinker" or b.type == "rightBlinker": if b.pressed: rear_view_toggle = True else: rear_view_toggle = False if b.type == "altButton1" and b.pressed: rear_view_toggle = not rear_view_toggle if not VP.brake_only and enabled and not b.pressed: if b.type == "accelCruise": v_cruise_kph = v_cruise_kph - ( v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA elif b.type == "decelCruise": v_cruise_kph = v_cruise_kph - ( v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) if not enabled and b.type in ["accelCruise", "decelCruise" ] and not b.pressed: enable_request = True # do disable on button down if b.type == "cancel" and b.pressed: AM.add("disable", enabled) prof.checkpoint("Buttons") # *** health checking logic *** hh = messaging.recv_sock(health) if hh is not None: # if the board isn't allowing controls but somehow we are enabled! if not hh.health.controlsAllowed and enabled: AM.add("controlsMismatch", enabled) # *** thermal checking logic *** # thermal data, checked every second td = messaging.recv_sock(thermal) if td is not None: # Check temperature. overtemp = any(t > 950 for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) # under 15% of space free free_space = td.thermal.freeSpace prof.checkpoint("Health") # *** getting model logic *** PP.update(cur_time, CS.vEgo) if rk.frame % 5 == 2: # *** run this at 20hz again *** angle_offset = learn_angle_offset(enabled, CS.vEgo, angle_offset, np.asarray(PP.d_poly), LaC.y_des, CS.steeringPressed) # disable if the pedals are pressed while engaged, this is a user disable if enabled: if CS.gasPressed or CS.brakePressed: AM.add("disable", enabled) if enable_request: # check for pressed pedals if CS.gasPressed or CS.brakePressed: AM.add("pedalPressed", enabled) enable_request = False else: print "enabled pressed at", cur_time last_enable_request = cur_time # don't engage with less than 15% free if free_space < 0.15: AM.add("outOfSpace", enabled) enable_request = False if VP.brake_only: enable_condition = ((cur_time - last_enable_request) < 0.2) and CS.cruiseState.enabled else: enable_condition = enable_request if enable_request or enable_condition or enabled: # add all alerts from car for alert in CS.errors: AM.add(alert, enabled) if AC.dead: AM.add("radarCommIssue", enabled) if PP.dead: AM.add("modelCommIssue", enabled) if overtemp: AM.add("overheat", enabled) prof.checkpoint("Model") if enable_condition and not enabled and not AM.alertPresent(): print "*** enabling controls" # beep for enabling AM.add("enable", enabled) # enable both lateral and longitudinal controls enabled = True # on activation, let's always set v_cruise from where we are, even if PCM ACC is active v_cruise_kph = int( round( max(CS.vEgo * CV.MS_TO_KPH * VP.ui_speed_fudge, V_CRUISE_ENABLE_MIN))) # 6 minutes driver you're on awareness_status = 1.0 # reset the PID loops LaC.reset() # start long control at actual speed LoC.reset(v_pid=CS.vEgo) if VP.brake_only and CS.cruiseState.enabled: v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # *** put the adaptive in adaptive cruise control *** AC.update(cur_time, CS.vEgo, CS.steeringAngle, LoC.v_pid, awareness_status, VP) prof.checkpoint("AdaptiveCruise") # *** gas/brake PID loop *** final_gas, final_brake = LoC.update(enabled, CS.vEgo, v_cruise_kph, AC.v_target_lead, AC.a_target, AC.jerk_factor, VP) # *** steering PID loop *** final_steer, sat_flag = LaC.update(enabled, CS.vEgo, CS.steeringAngle, CS.steeringPressed, PP.d_poly, angle_offset, VP) prof.checkpoint("PID") # ***** handle alerts **** # send a "steering required alert" if saturation count has reached the limit if sat_flag: AM.add("steerSaturated", enabled) if enabled and AM.alertShouldDisable(): print "DISABLING IMMEDIATELY ON ALERT" enabled = False if enabled and AM.alertShouldSoftDisable(): if soft_disable_timer is None: soft_disable_timer = 3 * rate elif soft_disable_timer == 0: print "SOFT DISABLING ON ALERT" enabled = False else: soft_disable_timer -= 1 else: soft_disable_timer = None # *** push the alerts to current *** alert_text_1, alert_text_2, visual_alert, audible_alert = AM.process_alerts( cur_time) # ***** control the car ***** CC = car.CarControl.new_message() CC.enabled = enabled CC.gas = float(final_gas) CC.brake = float(final_brake) CC.steeringTorque = float(final_steer) CC.cruiseControl.override = True CC.cruiseControl.cancel = bool( (not VP.brake_only) or (not enabled and CS.cruiseState.enabled )) # always cancel if we have an interceptor CC.cruiseControl.speedOverride = float((LoC.v_pid - .3) if ( VP.brake_only and final_brake == 0.) else 0.0) CC.cruiseControl.accelOverride = float(AC.a_pcm) CC.hudControl.setSpeed = float(v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = enabled CC.hudControl.lanesVisible = enabled CC.hudControl.leadVisible = bool(AC.has_lead) CC.hudControl.visualAlert = visual_alert CC.hudControl.audibleAlert = audible_alert # this alert will apply next controls cycle if not CI.apply(CC): AM.add("controlsFailed", enabled) prof.checkpoint("CarControl") # ***** publish state to logger ***** # publish controls state at 100Hz dat = messaging.new_message() dat.init('live100') # show rear view camera on phone if in reverse gear or when button is pressed dat.live100.rearViewCam = ('reverseGear' in CS.errors) or rear_view_toggle dat.live100.alertText1 = alert_text_1 dat.live100.alertText2 = alert_text_2 dat.live100.awarenessStatus = max(awareness_status, 0.0) if enabled else 0.0 # what packets were used to process dat.live100.canMonoTimes = list(CS.canMonoTimes) dat.live100.mdMonoTime = PP.logMonoTime dat.live100.l20MonoTime = AC.logMonoTime # if controls is enabled dat.live100.enabled = enabled # car state dat.live100.vEgo = CS.vEgo dat.live100.angleSteers = CS.steeringAngle dat.live100.steerOverride = CS.steeringPressed # longitudinal control state dat.live100.vPid = float(LoC.v_pid) dat.live100.vCruise = float(v_cruise_kph) dat.live100.upAccelCmd = float(LoC.Up_accel_cmd) dat.live100.uiAccelCmd = float(LoC.Ui_accel_cmd) # lateral control state dat.live100.yActual = float(LaC.y_actual) dat.live100.yDes = float(LaC.y_des) dat.live100.upSteer = float(LaC.Up_steer) dat.live100.uiSteer = float(LaC.Ui_steer) # processed radar state, should add a_pcm? dat.live100.vTargetLead = float(AC.v_target_lead) dat.live100.aTargetMin = float(AC.a_target[0]) dat.live100.aTargetMax = float(AC.a_target[1]) dat.live100.jerkFactor = float(AC.jerk_factor) # lag dat.live100.cumLagMs = -rk.remaining * 1000. live100.send(dat.to_bytes()) prof.checkpoint("Live100") # *** run loop at fixed rate *** if rk.keep_time(): prof.display()
class PCCController: def __init__(self, carcontroller): self.CC = carcontroller self.human_cruise_action_time = 0 self.pcc_available = self.prev_pcc_available = False self.pedal_timeout_frame = 0 self.accelerator_pedal_pressed = self.prev_accelerator_pedal_pressed = False self.automated_cruise_action_time = 0 self.last_angle = 0.0 self.radarState = messaging.sub_sock("radarState", conflate=True) self.live_map_data = messaging.sub_sock("liveMapData", conflate=True) self.lead_1 = None self.last_update_time = 0 self.enable_pedal_cruise = False self.stalk_pull_time_ms = 0 self.prev_stalk_pull_time_ms = -1000 self.prev_pcm_acc_status = 0 self.prev_cruise_buttons = CruiseButtons.IDLE self.pedal_speed_kph = 0.0 self.speed_limit_kph = 0.0 self.prev_speed_limit_kph = 0.0 self.pedal_idx = 0 self.pedal_steady = 0.0 self.prev_tesla_accel = 0.0 self.prev_tesla_pedal = 0.0 self.torqueLevel_last = 0.0 self.prev_v_ego = 0.0 self.PedalForZeroTorque = ( 18.0 # starting number for a S85, adjusts down automatically ) self.lastTorqueForPedalForZeroTorque = TORQUE_LEVEL_DECEL self.v_pid = 0.0 self.a_pid = 0.0 self.last_output_gb = 0.0 self.last_speed_kph = None # for smoothing the changes in speed self.v_acc_start = 0.0 self.a_acc_start = 0.0 self.v_acc = 0.0 self.v_acc_sol = 0.0 self.v_acc_future = 0.0 self.a_acc = 0.0 self.a_acc_sol = 0.0 self.v_cruise = 0.0 self.a_cruise = 0.0 # Long Control self.LoC = None # when was radar data last updated? self.lead_last_seen_time_ms = 0 self.continuous_lead_sightings = 0 self.params = Params() average_speed_over_x_suggestions = 6 # 0.3 seconds (20x a second) self.fleet_speed = FleetSpeed(average_speed_over_x_suggestions) def load_pid(self): try: v_pid_json = open(V_PID_FILE) data = json.load(v_pid_json) if self.LoC: if self.LoC.pid: self.LoC.pid.p = data["p"] self.LoC.pid.i = data["i"] if "d" not in data: self.LoC.pid.d = 0.01 else: self.LoC.pid.d = data["d"] self.LoC.pid.f = data["f"] else: print("self.LoC not initialized!") except: print("file not present, creating at next reset") # Helper function for saving the PCC pid constants across drives def save_pid(self, pid): data = {} data["p"] = pid.p data["i"] = pid.i data["d"] = pid.d data["f"] = pid.f try: with open(V_PID_FILE, "w") as outfile: json.dump(data, outfile) except IOError: print("PDD pid parameters could not be saved to file") def reset(self, v_pid): if self.LoC and RESET_PID_ON_DISENGAGE: self.LoC.reset(v_pid) def update_stat(self, CS, frame): if not self.LoC: self.LoC = LongControl(CS.CP, tesla_compute_gb) # Get v_id from the stored file when initiating the LoC and reset_on_disengage==false if not RESET_PID_ON_DISENGAGE: self.load_pid() self._update_pedal_state(CS, frame) can_sends = [] if not self.pcc_available: timed_out = frame >= self.pedal_timeout_frame if timed_out or CS.pedal_interceptor_state > 0: if self.prev_pcc_available: CS.UE.custom_alert_message( 4, "Pedal Interceptor %s" % ( "timed out" if timed_out else "fault (state %s)" % CS.pedal_interceptor_state ), 200, 4, ) if frame % 50 == 0: # send reset command idx = self.pedal_idx self.pedal_idx = (self.pedal_idx + 1) % 16 pedalcan = 2 if CS.useWithoutHarness: pedalcan = 0 can_sends.append( teslacan.create_pedal_command_msg(0, 0, idx, pedalcan) ) return can_sends prev_enable_pedal_cruise = self.enable_pedal_cruise # disable on brake if CS.brake_pressed and self.enable_pedal_cruise: self.enable_pedal_cruise = False self.reset(0.0) # process any stalk movement curr_time_ms = _current_time_millis() speed_uom_kph = 1.0 if CS.imperial_speed_units: speed_uom_kph = CV.MPH_TO_KPH if ( CS.cruise_buttons == CruiseButtons.MAIN and self.prev_cruise_buttons != CruiseButtons.MAIN ): self.prev_stalk_pull_time_ms = self.stalk_pull_time_ms self.stalk_pull_time_ms = curr_time_ms double_pull = ( self.stalk_pull_time_ms - self.prev_stalk_pull_time_ms < STALK_DOUBLE_PULL_MS ) ready = ( CS.cstm_btns.get_button_status(PCCModes.BUTTON_NAME) > PCCState.OFF and (CruiseState.is_off(CS.pcm_acc_status)) or CS.forcePedalOverCC ) if ready and double_pull: # A double pull enables ACC. updating the max ACC speed if necessary. self.enable_pedal_cruise = True self.reset(CS.v_ego) # Increase PCC speed to match current, if applicable. # We round the target speed in the user's units of measurement to avoid jumpy speed readings current_speed_kph_uom_rounded = ( int(CS.v_ego * CV.MS_TO_KPH / speed_uom_kph + 0.5) * speed_uom_kph ) self.pedal_speed_kph = max( current_speed_kph_uom_rounded, self.speed_limit_kph ) # Handle pressing the cancel button. elif CS.cruise_buttons == CruiseButtons.CANCEL: self.enable_pedal_cruise = False self.pedal_speed_kph = 0.0 self.stalk_pull_time_ms = 0 self.prev_stalk_pull_time_ms = -1000 # Handle pressing up and down buttons. elif self.enable_pedal_cruise and CS.cruise_buttons != self.prev_cruise_buttons: # Real stalk command while PCC is already enabled. Adjust the max PCC speed if necessary. # We round the target speed in the user's units of measurement to avoid jumpy speed readings actual_speed_kph_uom_rounded = ( int(CS.v_ego * CV.MS_TO_KPH / speed_uom_kph + 0.5) * speed_uom_kph ) if CS.cruise_buttons == CruiseButtons.RES_ACCEL: self.pedal_speed_kph = ( max(self.pedal_speed_kph, actual_speed_kph_uom_rounded) + speed_uom_kph ) elif CS.cruise_buttons == CruiseButtons.RES_ACCEL_2ND: self.pedal_speed_kph = ( max(self.pedal_speed_kph, actual_speed_kph_uom_rounded) + 5 * speed_uom_kph ) elif CS.cruise_buttons == CruiseButtons.DECEL_SET: self.pedal_speed_kph = self.pedal_speed_kph - speed_uom_kph elif CS.cruise_buttons == CruiseButtons.DECEL_2ND: self.pedal_speed_kph = self.pedal_speed_kph - 5 * speed_uom_kph # Clip PCC speed between 0 and 170 KPH. self.pedal_speed_kph = clip( self.pedal_speed_kph, MIN_PCC_V_KPH, MAX_PCC_V_KPH ) # If something disabled cruise control, disable PCC too elif self.enable_pedal_cruise and CS.pcm_acc_status and not CS.forcePedalOverCC: self.enable_pedal_cruise = False # A single pull disables PCC (falling back to just steering). Wait some time # in case a double pull comes along. elif ( self.enable_pedal_cruise and curr_time_ms - self.stalk_pull_time_ms > STALK_DOUBLE_PULL_MS and self.stalk_pull_time_ms - self.prev_stalk_pull_time_ms > STALK_DOUBLE_PULL_MS ): self.enable_pedal_cruise = False # Notify if PCC was toggled if prev_enable_pedal_cruise and not self.enable_pedal_cruise: CS.UE.custom_alert_message(3, "PCC Disabled", 150, 4) CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.STANDBY) self.fleet_speed.reset_averager() # save the pid parameters to params file self.save_pid(self.LoC.pid) elif self.enable_pedal_cruise and not prev_enable_pedal_cruise: CS.UE.custom_alert_message(2, "PCC Enabled", 150) CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.ENABLED) # Update the UI to show whether the current car state allows PCC. if CS.cstm_btns.get_button_status(PCCModes.BUTTON_NAME) in [ PCCState.STANDBY, PCCState.NOT_READY, ]: if CruiseState.is_off(CS.pcm_acc_status) or CS.forcePedalOverCC: CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.STANDBY) else: CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.NOT_READY) # Update prev state after all other actions. self.prev_cruise_buttons = CS.cruise_buttons self.prev_pcm_acc_status = CS.pcm_acc_status return can_sends def update_pdl( self, enabled, CS, frame, actuators, pcm_speed, pcm_override, speed_limit_ms, set_speed_limit_active, speed_limit_offset, alca_enabled, ): idx = self.pedal_idx self.prev_speed_limit_kph = self.speed_limit_kph ###################################################################################### # Determine pedal "zero" # # save position for cruising (zero acc, zero brake, no torque) when we are above 10 MPH ###################################################################################### if ( CS.torqueLevel < TORQUE_LEVEL_ACC and CS.torqueLevel > TORQUE_LEVEL_DECEL and CS.v_ego >= 10.0 * CV.MPH_TO_MS and abs(CS.torqueLevel) < abs(self.lastTorqueForPedalForZeroTorque) and self.prev_tesla_accel > 0.0 ): self.PedalForZeroTorque = self.prev_tesla_accel self.lastTorqueForPedalForZeroTorque = CS.torqueLevel # print ("Detected new Pedal For Zero Torque at %s" % (self.PedalForZeroTorque)) # print ("Torque level at detection %s" % (CS.torqueLevel)) # print ("Speed level at detection %s" % (CS.v_ego * CV.MS_TO_MPH)) if set_speed_limit_active and speed_limit_ms > 0: self.speed_limit_kph = (speed_limit_ms + speed_limit_offset) * CV.MS_TO_KPH if int(self.prev_speed_limit_kph) != int(self.speed_limit_kph): self.pedal_speed_kph = self.speed_limit_kph # reset MovingAverage for fleet speed when speed limit changes self.fleet_speed.reset_averager() else: # reset internal speed limit, so double pull doesn't set higher speed than current (e.g. after leaving the highway) self.speed_limit_kph = 0.0 self.pedal_idx = (self.pedal_idx + 1) % 16 if not self.pcc_available or not enabled: return 0.0, 0, idx # Alternative speed decision logic that uses the lead car's distance # and speed more directly. # Bring in the lead car distance from the radarState feed radSt = messaging.recv_one_or_none(self.radarState) mapd = messaging.recv_one_or_none(self.live_map_data) if radSt is not None: self.lead_1 = radSt.radarState.leadOne if _is_present(self.lead_1): self.lead_last_seen_time_ms = _current_time_millis() self.continuous_lead_sightings += 1 else: self.continuous_lead_sightings = 0 v_ego = CS.v_ego following = False if self.lead_1: following = ( self.lead_1.status and self.lead_1.dRel < MAX_RADAR_DISTANCE and self.lead_1.vLeadK > v_ego and self.lead_1.aLeadK > 0.0 ) accel_limits = [ float(x) for x in calc_cruise_accel_limits(v_ego, following) ] accel_limits[1] *= _accel_limit_multiplier(CS, self.lead_1) accel_limits[0] = _decel_limit( accel_limits[0], CS.v_ego, self.lead_1, CS, self.pedal_speed_kph ) jerk_limits = [ min(-0.1, accel_limits[0] / 2.0), max(0.1, accel_limits[1] / 2.0), ] # TODO: make a separate lookup for jerk tuning accel_limits = limit_accel_in_turns(v_ego, CS.angle_steers, accel_limits, CS.CP) output_gb = 0 #################################################################### # this mode (Follow) uses the Follow logic created by JJ for ACC # # once the speed is detected we have to use our own PID to determine # how much accel and break we have to do #################################################################### # Broken in 0.7.9 #if PCCModes.is_selected(FollowMode(), CS.cstm_btns): if False: MPC_BRAKE_MULTIPLIER = 6.0 enabled = self.enable_pedal_cruise and self.LoC.long_control_state in [ LongCtrlState.pid, LongCtrlState.stopping, ] # determine if pedal is pressed by human self.prev_accelerator_pedal_pressed = self.accelerator_pedal_pressed self.accelerator_pedal_pressed = CS.pedal_interceptor_value > 5 # reset PID if we just lifted foot of accelerator if ( not self.accelerator_pedal_pressed ) and self.prev_accelerator_pedal_pressed: self.reset(CS.v_ego) if self.enable_pedal_cruise and not self.accelerator_pedal_pressed: self.v_pid = self.calc_follow_speed_ms(CS, alca_enabled) or 0 if mapd is not None: v_curve = max_v_in_mapped_curve_ms( mapd.liveMapData, self.pedal_speed_kph ) if v_curve: self.v_pid = min(self.v_pid, v_curve) # take fleet speed into consideration self.v_pid = min( self.v_pid, self.fleet_speed.adjust( CS, self.pedal_speed_kph * CV.KPH_TO_MS, frame ), ) # cruise speed can't be negative even if user is distracted self.v_pid = max(self.v_pid, 0.0) self.v_cruise, self.a_cruise = speed_smoother( self.v_acc_start, self.a_acc_start, self.v_pid, accel_limits[1], accel_limits[0], jerk_limits[1], jerk_limits[0], _DT_MPC, ) # cruise speed can't be negative even is user is distracted self.v_cruise = max(self.v_cruise, 0.0) self.v_acc = self.v_cruise self.a_acc = self.a_cruise self.v_acc_future = self.v_pid # Interpolation of trajectory self.a_acc_sol = self.a_acc_start + (_DT / _DT_MPC) * ( self.a_acc - self.a_acc_start ) self.v_acc_sol = ( self.v_acc_start + _DT * (self.a_acc_sol + self.a_acc_start) / 2.0 ) self.v_acc_start = self.v_acc_sol self.a_acc_start = self.a_acc_sol # we will try to feed forward the pedal position.... we might want to feed the last_output_gb.... # op feeds forward self.a_acc_sol # it's all about testing now. vTarget = clip(self.v_acc_sol, 0, self.v_cruise) self.vTargetFuture = clip(self.v_acc_future, 0, self.v_pid) feedforward = self.a_acc_sol # feedforward = self.last_output_gb t_go, t_brake = self.LoC.update( self.enable_pedal_cruise, # randomly disabling stuff during 0.7.9 merge to prevent runtime crashes #CS.v_ego, #CS.brake_pressed != 0, #CS.standstill, #False, self.v_cruise, vTarget, self.vTargetFuture, feedforward, CS.CP, ) output_gb = t_go - t_brake # print ("Output GB Follow:", output_gb) else: self.reset(CS.v_ego) # print ("PID reset") output_gb = 0.0 starting = self.LoC.long_control_state == LongCtrlState.starting a_ego = min(CS.a_ego, 0.0) reset_speed = MIN_CAN_SPEED if starting else CS.v_ego reset_accel = CS.CP.startAccel if starting else a_ego self.v_acc = reset_speed self.a_acc = reset_accel self.v_acc_start = reset_speed self.a_acc_start = reset_accel self.v_cruise = reset_speed self.a_cruise = reset_accel self.v_acc_sol = reset_speed self.a_acc_sol = reset_accel self.v_pid = reset_speed self.last_speed_kph = None ############################################################## # This mode uses the longitudinal MPC built in OP # # we use the values from actuators.gas and actuators.brake ############################################################## #elif PCCModes.is_selected(OpMode(), CS.cstm_btns): else: output_gb = actuators.gas - actuators.brake self.v_pid = pcm_speed MPC_BRAKE_MULTIPLIER = 12.0 self.last_output_gb = output_gb # accel and brake apply_accel = clip( output_gb, 0.0, 1 ) # _accel_pedal_max(CS.v_ego, self.v_pid, self.lead_1, self.prev_tesla_accel, CS)) apply_brake = -clip( output_gb * MPC_BRAKE_MULTIPLIER, _brake_pedal_min( CS.v_ego, self.v_pid, self.lead_1, CS, self.pedal_speed_kph ), 0.0, ) # if speed is over 5mph, the "zero" is at PedalForZeroTorque; otherwise it is zero pedal_zero = 0.0 if CS.v_ego >= 5.0 * CV.MPH_TO_MS: pedal_zero = self.PedalForZeroTorque tesla_brake = clip((1.0 - apply_brake) * pedal_zero, 0, pedal_zero) tesla_accel = clip( apply_accel * (MAX_PEDAL_VALUE - pedal_zero), 0, MAX_PEDAL_VALUE - pedal_zero, ) tesla_pedal = tesla_brake + tesla_accel tesla_pedal = self.pedal_hysteresis(tesla_pedal, enabled) tesla_pedal = clip( tesla_pedal, self.prev_tesla_pedal - PEDAL_MAX_DOWN, self.prev_tesla_pedal + PEDAL_MAX_UP, ) tesla_pedal = ( clip(tesla_pedal, 0.0, MAX_PEDAL_VALUE) if self.enable_pedal_cruise else 0.0 ) enable_pedal = 1.0 if self.enable_pedal_cruise else 0.0 self.torqueLevel_last = CS.torqueLevel self.prev_tesla_pedal = tesla_pedal * enable_pedal self.prev_tesla_accel = apply_accel * enable_pedal self.prev_v_ego = CS.v_ego return self.prev_tesla_pedal, enable_pedal, idx # function to calculate the cruise speed based on a safe follow distance def calc_follow_speed_ms(self, CS, alca_enabled): # Make sure we were able to populate lead_1. if self.lead_1 is None: return None # dRel is in meters. lead_dist_m = self.lead_1.dRel if not CS.useTeslaRadar: lead_dist_m = _visual_radar_adjusted_dist_m(lead_dist_m, CS) # Grab the relative speed. v_rel = self.lead_1.vRel if abs(self.lead_1.vRel) > 0.5 else 0 a_rel = self.lead_1.aRel if abs(self.lead_1.aRel) > 0.5 else 0 rel_speed_kph = (v_rel + 0 * CS.apFollowTimeInS * a_rel) * CV.MS_TO_KPH # v_ego is in m/s, so safe_distance is in meters. safe_dist_m = _safe_distance_m(CS.v_ego, CS) # Current speed in kph actual_speed_kph = CS.v_ego * CV.MS_TO_KPH # speed and brake to issue if self.last_speed_kph is None: self.last_speed_kph = actual_speed_kph new_speed_kph = self.last_speed_kph ### Logic to determine best cruise speed ### if self.enable_pedal_cruise: # If no lead is present, accel up to max speed if lead_dist_m == 0 or lead_dist_m > MAX_RADAR_DISTANCE: new_speed_kph = self.pedal_speed_kph elif lead_dist_m > 0: # BB Use the Kalman lead speed and acceleration lead_absolute_speed_kph = ( actual_speed_kph + rel_speed_kph ) # (self.lead_1.vLeadK + _DT * self.lead_1.aLeadK) * CV.MS_TO_KPH rel_speed_kph = lead_absolute_speed_kph - actual_speed_kph if lead_dist_m < MIN_SAFE_DIST_M and rel_speed_kph >= 3: # If lead is going faster, but we're not at a safe distance, hold # speed and let the lead car move father away from us new_speed_kph = actual_speed_kph # If lead is not going faster than 3kpm from us, lets slow down a # bit to get him moving faster relative to us elif lead_dist_m < MIN_SAFE_DIST_M: new_speed_kph = MIN_PCC_V_KPH # In a 10 meter cruise zone, lets match the car in front elif ( safe_dist_m + 2 > lead_dist_m > MIN_SAFE_DIST_M ): # BB we might want to try this and rel_speed_kph > 0: min_vrel_kph_map = OrderedDict( [ # (distance in m, min allowed relative kph) (0.5 * safe_dist_m, 3.0), (0.8 * safe_dist_m, 2.0), (1.0 * safe_dist_m, 0.0), ] ) min_vrel_kph = _interp_map(lead_dist_m, min_vrel_kph_map) new_speed_kph = lead_absolute_speed_kph - min_vrel_kph else: # Force speed into a band that is generally slower than lead if too # close, and faster than lead if too far. Allow a range of speeds at # any given distance, to prevent continuous jerky adjustments. # BB band should be % of v_ego min_vrel_kph_map = OrderedDict( [ # (distance in m, min allowed relative kph) (0.5 * safe_dist_m, 3), (1.0 * safe_dist_m, -1 - 0.025 * CS.v_ego * CV.MS_TO_KPH), (1.5 * safe_dist_m, -5 - 0.05 * CS.v_ego * CV.MS_TO_KPH), (3.0 * safe_dist_m, -10 - 0.1 * CS.v_ego * CV.MS_TO_KPH), ] ) min_vrel_kph = _interp_map(lead_dist_m, min_vrel_kph_map) max_vrel_kph_map = OrderedDict( [ # (distance in m, max allowed relative kph) (0.5 * safe_dist_m, 6), (1.0 * safe_dist_m, 2), (1.5 * safe_dist_m, -3), # With visual radar the relative velocity is 0 until the confidence # gets high. So even a small negative number here gives constant # accel until lead lead car gets close enough to read. (3 * safe_dist_m, -7), ] ) max_vrel_kph = _interp_map(lead_dist_m, max_vrel_kph_map) # if CS.useTeslaRadar: # min_vrel_kph = -1 # max_vrel_kph = -2 min_kph = lead_absolute_speed_kph - max_vrel_kph max_kph = lead_absolute_speed_kph - min_vrel_kph # In the special case were we are going faster than intended but it's # still an acceptable speed, accept it. This could happen if the # driver manually accelerates, or if we roll down a hill. In either # case, don't fight the extra velocity unless necessary. if ( lead_dist_m >= 0.8 * safe_dist_m and lead_absolute_speed_kph > actual_speed_kph and self.lead_1.aLeadK >= 0.0 ): new_speed_kph = lead_absolute_speed_kph new_speed_kph = clip(new_speed_kph, min_kph, max_kph) if ( (actual_speed_kph > new_speed_kph) and (min_kph < actual_speed_kph < max_kph) and (lead_absolute_speed_kph > 30) ): new_speed_kph = actual_speed_kph # BB disabled this condition as it might not allow fast enough braking # if (actual_speed_kph > 80) and abs(actual_speed_kph - new_speed_kph) < 3.: # new_speed_kph = (actual_speed_kph + new_speed_kph)/2.0 # Enforce limits on speed in the presence of a lead car. new_speed_kph = min( new_speed_kph, _max_safe_speed_kph(self.lead_1, CS), max( lead_absolute_speed_kph - _min_safe_vrel_kph(self.lead_1, CS, actual_speed_kph), 2, ), ) # Enforce limits on speed new_speed_kph = clip(new_speed_kph, MIN_PCC_V_KPH, MAX_PCC_V_KPH) new_speed_kph = clip(new_speed_kph, MIN_PCC_V_KPH, self.pedal_speed_kph) if ( CS.turn_signal_blinking or (abs(CS.angle_steers) > ANGLE_STOP_ACCEL) or alca_enabled ): # Don't accelerate during manual turns, curves or ALCA. new_speed_kph = min(new_speed_kph, self.last_speed_kph) # BB Last safety check. Zero if below MIN_SAFE_DIST_M if (MIN_SAFE_DIST_M > lead_dist_m > 0) and (rel_speed_kph < 3.0): new_speed_kph = MIN_PCC_V_KPH self.last_speed_kph = new_speed_kph return new_speed_kph * CV.KPH_TO_MS def pedal_hysteresis(self, pedal, enabled): # for small accel oscillations within PEDAL_HYST_GAP, don't change the command if not enabled: # send 0 when disabled, otherwise acc faults self.pedal_steady = 0.0 elif pedal > self.pedal_steady + PEDAL_HYST_GAP: self.pedal_steady = pedal - PEDAL_HYST_GAP elif pedal < self.pedal_steady - PEDAL_HYST_GAP: self.pedal_steady = pedal + PEDAL_HYST_GAP return self.pedal_steady def _update_pedal_state(self, CS, frame): if CS.pedal_idx != CS.prev_pedal_idx: # time out pedal after 500ms without receiving a new CAN message from it self.pedal_timeout_frame = frame + 50 self.prev_pcc_available = self.pcc_available pedal_ready = ( frame < self.pedal_timeout_frame and CS.pedal_interceptor_state == 0 ) acc_disabled = CS.forcePedalOverCC or CruiseState.is_off(CS.pcm_acc_status) # Mark pedal unavailable while traditional cruise is on. self.pcc_available = pedal_ready and acc_disabled if self.pcc_available != self.prev_pcc_available: CS.config_ui_buttons(self.pcc_available, pedal_ready and not acc_disabled)
def controlsd_thread(gctx, rate=100): #rate in Hz # *** log *** context = zmq.Context() live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) thermal = messaging.sub_sock(context, service_list['thermal'].port) health = messaging.sub_sock(context, service_list['health'].port) plan_sock = messaging.sub_sock(context, service_list['plan'].port) logcan = messaging.sub_sock(context, service_list['can'].port) # connects to can CP = fingerprint(logcan) # import the car from the fingerprint cloudlog.info("controlsd is importing %s", CP.carName) exec('from selfdrive.car.' + CP.carName + '.interface import CarInterface') sendcan = messaging.pub_sock(context, service_list['sendcan'].port) CI = CarInterface(CP, logcan, sendcan) # write CarParams params = Params() params.put("CarParams", CP.to_bytes()) AM = AlertManager() LoC = LongControl() LaC = LatControl() # fake plan plan = log.Plan.new_message() plan.lateralValid = False plan.longitudinalValid = False last_plan_time = 0 # controls enabled state enabled = False last_enable_request = 0 # learned angle offset angle_offset = 0 # rear view camera state rear_view_toggle = False rear_view_allowed = bool(params.get("IsRearViewMirror")) v_cruise_kph = 255 # 0.0 - 1.0 awareness_status = 0.0 soft_disable_timer = None # Is cpu temp too high to enable? overtemp = False free_space = 1.0 # start the loop set_realtime_priority(2) rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) while 1: cur_time = sec_since_boot() prof = Profiler() # read CAN CS = CI.update() prof.checkpoint("CarInterface") # broadcast carState cs_send = messaging.new_message() cs_send.init('carState') cs_send.carState = CS # copy? carstate.send(cs_send.to_bytes()) prof.checkpoint("CarState") # did it request to enable? enable_request, enable_condition = False, False if enabled: # gives the user 6 minutes awareness_status -= 1.0 / (100 * 60 * 6) if awareness_status <= 0.: AM.add("driverDistracted", enabled) # reset awareness status on steering if CS.steeringPressed: awareness_status = 1.0 # handle button presses for b in CS.buttonEvents: print b # reset awareness on any user action awareness_status = 1.0 # button presses for rear view if b.type == "leftBlinker" or b.type == "rightBlinker": if b.pressed and rear_view_allowed: rear_view_toggle = True else: rear_view_toggle = False if b.type == "altButton1" and b.pressed: rear_view_toggle = not rear_view_toggle if not CP.enableCruise and enabled and not b.pressed: if b.type == "accelCruise": v_cruise_kph = v_cruise_kph - ( v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA elif b.type == "decelCruise": v_cruise_kph = v_cruise_kph - ( v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA v_cruise_kph = clip(v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) if not enabled and b.type in ["accelCruise", "decelCruise" ] and not b.pressed: enable_request = True # do disable on button down if b.type == "cancel" and b.pressed: AM.add("disable", enabled) prof.checkpoint("Buttons") # *** health checking logic *** hh = messaging.recv_sock(health) if hh is not None: # if the board isn't allowing controls but somehow we are enabled! if not hh.health.controlsAllowed and enabled: AM.add("controlsMismatch", enabled) # *** thermal checking logic *** # thermal data, checked every second td = messaging.recv_sock(thermal) if td is not None: # Check temperature. overtemp = any(t > 950 for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) # under 15% of space free free_space = td.thermal.freeSpace prof.checkpoint("Health") # disable if the pedals are pressed while engaged, this is a user disable if enabled: if CS.gasPressed or CS.brakePressed: AM.add("disable", enabled) # how did we get into this state? if CP.enableCruise and not CS.cruiseState.enabled: AM.add("cruiseDisabled", enabled) if enable_request: # check for pressed pedals if CS.gasPressed or CS.brakePressed: AM.add("pedalPressed", enabled) enable_request = False else: print "enabled pressed at", cur_time last_enable_request = cur_time # don't engage with less than 15% free if free_space < 0.15: AM.add("outOfSpace", enabled) enable_request = False if CP.enableCruise: enable_condition = ((cur_time - last_enable_request) < 0.2) and CS.cruiseState.enabled else: enable_condition = enable_request if CP.enableCruise and CS.cruiseState.enabled: v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH prof.checkpoint("AdaptiveCruise") # *** what's the plan *** new_plan = messaging.recv_sock(plan_sock) if new_plan is not None: plan = new_plan.plan plan = plan.as_builder() # plan can change in controls last_plan_time = cur_time # check plan for timeout if cur_time - last_plan_time > 0.5: plan.lateralValid = False plan.longitudinalValid = False # gives 18 seconds before decel begins (w 6 minute timeout) if awareness_status < -0.05: plan.aTargetMax = min(plan.aTargetMax, -0.2) plan.aTargetMin = min(plan.aTargetMin, plan.aTargetMax) if enable_request or enable_condition or enabled: # add all alerts from car for alert in CS.errors: AM.add(alert, enabled) if not plan.longitudinalValid: AM.add("radarCommIssue", enabled) if not plan.lateralValid: # If the model is not broadcasting, assume that it is because # the user has uploaded insufficient data for calibration. # Other cases that would trigger this are rare and unactionable by the user. AM.add("dataNeeded", enabled) if overtemp: AM.add("overheat", enabled) # *** angle offset learning *** if rk.frame % 5 == 2 and plan.lateralValid: # *** run this at 20hz again *** angle_offset = learn_angle_offset(enabled, CS.vEgo, angle_offset, plan.dPoly, LaC.y_des, CS.steeringPressed) # *** gas/brake PID loop *** final_gas, final_brake = LoC.update(enabled, CS.vEgo, v_cruise_kph, plan.vTarget, [plan.aTargetMin, plan.aTargetMax], plan.jerkFactor, CP) # *** steering PID loop *** final_steer, sat_flag = LaC.update(enabled, CS.vEgo, CS.steeringAngle, CS.steeringPressed, plan.dPoly, angle_offset, CP) prof.checkpoint("PID") # ***** handle alerts **** # send a "steering required alert" if saturation count has reached the limit if sat_flag: AM.add("steerSaturated", enabled) if enabled and AM.alertShouldDisable(): print "DISABLING IMMEDIATELY ON ALERT" enabled = False if enabled and AM.alertShouldSoftDisable(): if soft_disable_timer is None: soft_disable_timer = 3 * rate elif soft_disable_timer == 0: print "SOFT DISABLING ON ALERT" enabled = False else: soft_disable_timer -= 1 else: soft_disable_timer = None if enable_condition and not enabled and not AM.alertPresent(): print "*** enabling controls" # beep for enabling AM.add("enable", enabled) # enable both lateral and longitudinal controls enabled = True # on activation, let's always set v_cruise from where we are, even if PCM ACC is active v_cruise_kph = int( round(max(CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN))) # 6 minutes driver you're on awareness_status = 1.0 # reset the PID loops LaC.reset() # start long control at actual speed LoC.reset(v_pid=CS.vEgo) # *** push the alerts to current *** alert_text_1, alert_text_2, visual_alert, audible_alert = AM.process_alerts( cur_time) # ***** control the car ***** CC = car.CarControl.new_message() CC.enabled = enabled CC.gas = float(final_gas) CC.brake = float(final_brake) CC.steeringTorque = float(final_steer) CC.cruiseControl.override = True CC.cruiseControl.cancel = bool( (not CP.enableCruise) or (not enabled and CS.cruiseState.enabled )) # always cancel if we have an interceptor # brake discount removes a sharp nonlinearity brake_discount = (1.0 - clip(final_brake * 3., 0.0, 1.0)) CC.cruiseControl.speedOverride = float( max(0.0, ((LoC.v_pid - .5) * brake_discount)) if CP.enableCruise else 0.0) #CC.cruiseControl.accelOverride = float(AC.a_pcm) # TODO: fix this CC.cruiseControl.accelOverride = float(1.0) CC.hudControl.setSpeed = float(v_cruise_kph * CV.KPH_TO_MS) CC.hudControl.speedVisible = enabled CC.hudControl.lanesVisible = enabled CC.hudControl.leadVisible = plan.hasLead CC.hudControl.visualAlert = visual_alert CC.hudControl.audibleAlert = audible_alert # this alert will apply next controls cycle if not CI.apply(CC): AM.add("controlsFailed", enabled) # broadcast carControl cc_send = messaging.new_message() cc_send.init('carControl') cc_send.carControl = CC # copy? carcontrol.send(cc_send.to_bytes()) prof.checkpoint("CarControl") # ***** publish state to logger ***** # publish controls state at 100Hz dat = messaging.new_message() dat.init('live100') # show rear view camera on phone if in reverse gear or when button is pressed dat.live100.rearViewCam = ('reverseGear' in CS.errors and rear_view_allowed) or rear_view_toggle dat.live100.alertText1 = alert_text_1 dat.live100.alertText2 = alert_text_2 dat.live100.awarenessStatus = max(awareness_status, 0.0) if enabled else 0.0 # what packets were used to process dat.live100.canMonoTimes = list(CS.canMonoTimes) # if controls is enabled dat.live100.enabled = enabled # car state dat.live100.vEgo = CS.vEgo dat.live100.angleSteers = CS.steeringAngle dat.live100.steerOverride = CS.steeringPressed # longitudinal control state dat.live100.vPid = float(LoC.v_pid) dat.live100.vCruise = float(v_cruise_kph) dat.live100.upAccelCmd = float(LoC.Up_accel_cmd) dat.live100.uiAccelCmd = float(LoC.Ui_accel_cmd) # lateral control state dat.live100.yActual = float(LaC.y_actual) dat.live100.yDes = float(LaC.y_des) dat.live100.upSteer = float(LaC.Up_steer) dat.live100.uiSteer = float(LaC.Ui_steer) # processed radar state, should add a_pcm? dat.live100.vTargetLead = float(plan.vTarget) dat.live100.aTargetMin = float(plan.aTargetMin) dat.live100.aTargetMax = float(plan.aTargetMax) dat.live100.jerkFactor = float(plan.jerkFactor) # log learned angle offset dat.live100.angleOffset = float(angle_offset) # lag dat.live100.cumLagMs = -rk.remaining * 1000. live100.send(dat.to_bytes()) prof.checkpoint("Live100") # *** run loop at fixed rate *** if rk.keep_time(): prof.display()
def update_stat(self, CS, frame): if not self.LoC: self.LoC = LongControl(CS.CP, tesla_compute_gb) # Get v_id from the stored file when initiating the LoC and reset_on_disengage==false if not RESET_PID_ON_DISENGAGE: self.load_pid() self._update_pedal_state(CS, frame) can_sends = [] if not self.pcc_available: timed_out = frame >= self.pedal_timeout_frame if timed_out or CS.pedal_interceptor_state > 0: if self.prev_pcc_available: CS.UE.custom_alert_message( 4, "Pedal Interceptor %s" % ( "timed out" if timed_out else "fault (state %s)" % CS.pedal_interceptor_state ), 200, 4, ) if frame % 50 == 0: # send reset command idx = self.pedal_idx self.pedal_idx = (self.pedal_idx + 1) % 16 pedalcan = 2 if CS.useWithoutHarness: pedalcan = 0 can_sends.append( teslacan.create_pedal_command_msg(0, 0, idx, pedalcan) ) return can_sends prev_enable_pedal_cruise = self.enable_pedal_cruise # disable on brake if CS.brake_pressed and self.enable_pedal_cruise: self.enable_pedal_cruise = False self.reset(0.0) # process any stalk movement curr_time_ms = _current_time_millis() speed_uom_kph = 1.0 if CS.imperial_speed_units: speed_uom_kph = CV.MPH_TO_KPH if ( CS.cruise_buttons == CruiseButtons.MAIN and self.prev_cruise_buttons != CruiseButtons.MAIN ): self.prev_stalk_pull_time_ms = self.stalk_pull_time_ms self.stalk_pull_time_ms = curr_time_ms double_pull = ( self.stalk_pull_time_ms - self.prev_stalk_pull_time_ms < STALK_DOUBLE_PULL_MS ) ready = ( CS.cstm_btns.get_button_status(PCCModes.BUTTON_NAME) > PCCState.OFF and (CruiseState.is_off(CS.pcm_acc_status)) or CS.forcePedalOverCC ) if ready and double_pull: # A double pull enables ACC. updating the max ACC speed if necessary. self.enable_pedal_cruise = True self.reset(CS.v_ego) # Increase PCC speed to match current, if applicable. # We round the target speed in the user's units of measurement to avoid jumpy speed readings current_speed_kph_uom_rounded = ( int(CS.v_ego * CV.MS_TO_KPH / speed_uom_kph + 0.5) * speed_uom_kph ) self.pedal_speed_kph = max( current_speed_kph_uom_rounded, self.speed_limit_kph ) # Handle pressing the cancel button. elif CS.cruise_buttons == CruiseButtons.CANCEL: self.enable_pedal_cruise = False self.pedal_speed_kph = 0.0 self.stalk_pull_time_ms = 0 self.prev_stalk_pull_time_ms = -1000 # Handle pressing up and down buttons. elif self.enable_pedal_cruise and CS.cruise_buttons != self.prev_cruise_buttons: # Real stalk command while PCC is already enabled. Adjust the max PCC speed if necessary. # We round the target speed in the user's units of measurement to avoid jumpy speed readings actual_speed_kph_uom_rounded = ( int(CS.v_ego * CV.MS_TO_KPH / speed_uom_kph + 0.5) * speed_uom_kph ) if CS.cruise_buttons == CruiseButtons.RES_ACCEL: self.pedal_speed_kph = ( max(self.pedal_speed_kph, actual_speed_kph_uom_rounded) + speed_uom_kph ) elif CS.cruise_buttons == CruiseButtons.RES_ACCEL_2ND: self.pedal_speed_kph = ( max(self.pedal_speed_kph, actual_speed_kph_uom_rounded) + 5 * speed_uom_kph ) elif CS.cruise_buttons == CruiseButtons.DECEL_SET: self.pedal_speed_kph = self.pedal_speed_kph - speed_uom_kph elif CS.cruise_buttons == CruiseButtons.DECEL_2ND: self.pedal_speed_kph = self.pedal_speed_kph - 5 * speed_uom_kph # Clip PCC speed between 0 and 170 KPH. self.pedal_speed_kph = clip( self.pedal_speed_kph, MIN_PCC_V_KPH, MAX_PCC_V_KPH ) # If something disabled cruise control, disable PCC too elif self.enable_pedal_cruise and CS.pcm_acc_status and not CS.forcePedalOverCC: self.enable_pedal_cruise = False # A single pull disables PCC (falling back to just steering). Wait some time # in case a double pull comes along. elif ( self.enable_pedal_cruise and curr_time_ms - self.stalk_pull_time_ms > STALK_DOUBLE_PULL_MS and self.stalk_pull_time_ms - self.prev_stalk_pull_time_ms > STALK_DOUBLE_PULL_MS ): self.enable_pedal_cruise = False # Notify if PCC was toggled if prev_enable_pedal_cruise and not self.enable_pedal_cruise: CS.UE.custom_alert_message(3, "PCC Disabled", 150, 4) CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.STANDBY) self.fleet_speed.reset_averager() # save the pid parameters to params file self.save_pid(self.LoC.pid) elif self.enable_pedal_cruise and not prev_enable_pedal_cruise: CS.UE.custom_alert_message(2, "PCC Enabled", 150) CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.ENABLED) # Update the UI to show whether the current car state allows PCC. if CS.cstm_btns.get_button_status(PCCModes.BUTTON_NAME) in [ PCCState.STANDBY, PCCState.NOT_READY, ]: if CruiseState.is_off(CS.pcm_acc_status) or CS.forcePedalOverCC: CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.STANDBY) else: CS.cstm_btns.set_button_status(PCCModes.BUTTON_NAME, PCCState.NOT_READY) # Update prev state after all other actions. self.prev_cruise_buttons = CS.cruise_buttons self.prev_pcm_acc_status = CS.pcm_acc_status return can_sends
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: self.sm = messaging.SubMaster([ 'thermal', 'health', 'model', 'liveCalibration', 'frontFrame', 'dMonitoringState', 'plan', 'pathPlan', 'liveLocationKalman' ]) 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 health 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 params = Params() self.is_metric = params.get("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" internet_needed = (params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None) and ( params.get("DisableUpdates") != b"1") community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ internet_needed 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) self.lateral_control_method = 0 if self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP) self.lateral_control_method = 0 elif self.CP.lateralTuning.which() == 'indi': self.LaC = LatControlINDI(self.CP) self.lateral_control_method = 1 elif self.CP.lateralTuning.which() == 'lqr': self.LaC = LatControlLQR(self.CP) self.lateral_control_method = 2 self.controlsAllowed = 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.sm['liveCalibration'].calStatus = Calibration.CALIBRATED self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False self.startup_event = get_startup_event(car_recognized, controller_available) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) #if internet_needed: # self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, 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 self.hyundai_lkas = self.read_only #read_only
def controlsd_thread(sm=None, pm=None, can_sock=None): gc.disable() # start the loop set_realtime_priority(3) params = Params() is_metric = params.get("IsMetric", encoding='utf8') == "1" is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" passive = passive or not openpilot_enabled_toggle # Passive if internet needed internet_needed = params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None passive = passive or internet_needed # Pub/Sub Sockets if pm is None: pm = messaging.PubMaster([ 'sendcan', 'controlsState', 'carState', 'carControl', 'carEvents', 'carParams' ]) if sm is None: sm = messaging.SubMaster(['thermal', 'health', 'liveCalibration', 'dMonitoringState', 'plan', 'pathPlan', \ 'model']) if can_sock is None: can_timeout = None if os.environ.get('NO_CAN_TIMEOUT', False) else 100 can_sock = messaging.sub_sock('can', timeout=can_timeout) # wait for health and CAN packets hw_type = messaging.recv_one(sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno] print("Waiting for CAN messages...") messaging.get_one_can(can_sock) CI, CP = get_car(can_sock, pm.sock['sendcan'], has_relay) car_recognized = CP.carName != 'mock' # If stock camera is disconnected, we loaded car controls and it's not chffrplus controller_available = CP.enableCamera and CI.CC is not None and not passive community_feature_disallowed = CP.communityFeature and not community_feature_toggle read_only = not car_recognized or not controller_available or CP.dashcamOnly or community_feature_disallowed if read_only: CP.safetyModel = car.CarParams.SafetyModel.noOutput # Write CarParams for radard and boardd safety mode cp_bytes = CP.to_bytes() params.put("CarParams", cp_bytes) put_nonblocking("CarParamsCache", cp_bytes) put_nonblocking("LongitudinalControl", "1" if CP.openpilotLongitudinalControl else "0") CC = car.CarControl.new_message() AM = AlertManager() startup_alert = get_startup_alert(car_recognized, controller_available) AM.add(sm.frame, startup_alert, False) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) if CP.lateralTuning.which() == 'pid': LaC = LatControlPID(CP) elif CP.lateralTuning.which() == 'indi': LaC = LatControlINDI(CP) elif CP.lateralTuning.which() == 'lqr': LaC = LatControlLQR(CP) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 mismatch_counter = 0 can_error_counter = 0 last_blinker_frame = 0 saturated_count = 0 events_prev = [] sm['liveCalibration'].calStatus = Calibration.INVALID sm['pathPlan'].sensorValid = True sm['pathPlan'].posenetValid = True sm['thermal'].freeSpace = 1. sm['dMonitoringState'].events = [] sm['dMonitoringState'].awarenessStatus = 1. sm['dMonitoringState'].faceDetected = False # detect sound card presence sounds_available = not os.path.isfile('/EON') or ( os.path.isdir('/proc/asound/card0') and open('/proc/asound/card0/state').read().strip() == 'ONLINE') # controlsd is driven by can recv, expected at 100Hz rk = Ratekeeper(100, print_delay_threshold=None) prof = Profiler(False) # off by default while True: start_time = sec_since_boot() prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_perc, mismatch_counter, can_error_counter = data_sample( CI, CC, sm, can_sock, state, mismatch_counter, can_error_counter, params) prof.checkpoint("Sample") # Create alerts if not sm.alive['plan'] and sm.alive[ 'pathPlan']: # only plan not being received: radar not communicating events.append( create_event('radarCommIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) elif not sm.all_alive_and_valid(): events.append( create_event('commIssue', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not sm['pathPlan'].mpcSolutionValid: events.append( create_event('plannerError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not sm['pathPlan'].sensorValid and os.getenv("NOSENSOR") is None: events.append( create_event('sensorDataInvalid', [ET.NO_ENTRY, ET.PERMANENT])) if not sm['pathPlan'].paramsValid: events.append(create_event('vehicleModelInvalid', [ET.WARNING])) if not sm['pathPlan'].posenetValid: events.append( create_event('posenetInvalid', [ET.NO_ENTRY, ET.WARNING])) if not sm['plan'].radarValid: events.append( create_event('radarFault', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if sm['plan'].radarCanError: events.append( create_event('radarCanError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) if not CS.canValid: events.append( create_event('canError', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not sounds_available: events.append( create_event('soundsUnavailable', [ET.NO_ENTRY, ET.PERMANENT])) if internet_needed: events.append( create_event('internetConnectivityNeeded', [ET.NO_ENTRY, ET.PERMANENT])) if community_feature_disallowed: events.append( create_event('communityFeatureDisallowed', [ET.PERMANENT])) if read_only and not passive: events.append(create_event('carUnrecognized', [ET.PERMANENT])) if log.HealthData.FaultType.relayMalfunction in sm['health'].faults: events.append( create_event( 'relayMalfunction', [ET.NO_ENTRY, ET.PERMANENT, ET.IMMEDIATE_DISABLE])) # Only allow engagement with brake pressed when stopped behind another stopped car #if CS.brakePressed and sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: # events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not read_only: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(sm.frame, CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, v_acc, a_acc, lac_log, last_blinker_frame, saturated_count = \ state_control(sm.frame, sm.rcv_frame, sm['plan'], sm['pathPlan'], CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, LaC, LoC, read_only, is_metric, cal_perc, last_blinker_frame, saturated_count) prof.checkpoint("State Control") # Publish data CC, events_prev = data_send(sm, pm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, AM, LaC, LoC, read_only, start_time, v_acc, a_acc, lac_log, events_prev, last_blinker_frame, is_ldw_enabled, can_error_counter) prof.checkpoint("Sent") rk.monitor_time() prof.display()
class Controls(object): def __init__(self, gctx, rate=100): self.rate = rate # *** log *** context = zmq.Context() # pub self.live100 = messaging.pub_sock(context, service_list['live100'].port) self.carstate = messaging.pub_sock(context, service_list['carState'].port) self.carcontrol = messaging.pub_sock(context, service_list['carControl'].port) sendcan = messaging.pub_sock(context, service_list['sendcan'].port) # sub self.thermal = messaging.sub_sock(context, service_list['thermal'].port) self.health = messaging.sub_sock(context, service_list['health'].port) logcan = messaging.sub_sock(context, service_list['can'].port) self.cal = messaging.sub_sock(context, service_list['liveCalibration'].port) self.CC = car.CarControl.new_message() self.CI, self.CP = get_car(logcan, sendcan) self.PL = Planner(self.CP) self.AM = AlertManager() self.LoC = LongControl() self.LaC = LatControl() # write CarParams params = Params() params.put("CarParams", self.CP.to_bytes()) # fake plan self.plan_ts = 0 self.plan = log.Plan.new_message() self.plan.lateralValid = False self.plan.longitudinalValid = False # controls enabled state self.enabled = False self.last_enable_request = 0 # learned angle offset self.angle_offset = 0 # rear view camera state self.rear_view_toggle = False self.rear_view_allowed = bool(params.get("IsRearViewMirror")) self.v_cruise_kph = 255 # 0.0 - 1.0 self.awareness_status = 1.0 self.soft_disable_timer = None self.overtemp = False self.free_space = 1.0 self.cal_status = Calibration.UNCALIBRATED self.cal_perc = 0 self.rk = Ratekeeper(self.rate, print_delay_threshold=2. / 1000) def data_sample(self): self.prof = Profiler() self.cur_time = sec_since_boot() # first read can and compute car states self.CS = self.CI.update() self.prof.checkpoint("CarInterface") # *** thermal checking logic *** # thermal data, checked every second td = messaging.recv_sock(self.thermal) if td is not None: # Check temperature. self.overtemp = any(t > 950 for t in (td.thermal.cpu0, td.thermal.cpu1, td.thermal.cpu2, td.thermal.cpu3, td.thermal.mem, td.thermal.gpu)) # under 15% of space free self.free_space = td.thermal.freeSpace # read calibration status cal = messaging.recv_sock(self.cal) #print "========= cal" #print cal if cal is not None: self.cal_status = cal.liveCalibration.calStatus self.cal_perc = cal.liveCalibration.calPerc def state_transition(self): pass # for now def state_control(self): # did it request to enable? enable_request, enable_condition = False, False # reset awareness status on steering if self.CS.steeringPressed or not self.enabled: self.awareness_status = 1.0 elif self.enabled: # gives the user 6 minutes self.awareness_status -= 1.0 / (self.rate * AWARENESS_TIME) if self.awareness_status <= 0.: self.AM.add("driverDistracted", self.enabled) elif self.awareness_status <= AWARENESS_PRE_TIME / AWARENESS_TIME and \ self.awareness_status >= (AWARENESS_PRE_TIME - 0.1) / AWARENESS_TIME: self.AM.add("preDriverDistracted", self.enabled) # handle button presses for b in self.CS.buttonEvents: print b # button presses for rear view if b.type == "leftBlinker" or b.type == "rightBlinker": if b.pressed and self.rear_view_allowed: self.rear_view_toggle = True else: self.rear_view_toggle = False if b.type == "altButton1" and b.pressed: self.rear_view_toggle = not self.rear_view_toggle if not self.CP.enableCruise and self.enabled and not b.pressed: if b.type == "accelCruise": self.v_cruise_kph -= (self.v_cruise_kph % V_CRUISE_DELTA) - V_CRUISE_DELTA elif b.type == "decelCruise": self.v_cruise_kph -= (self.v_cruise_kph % V_CRUISE_DELTA) + V_CRUISE_DELTA self.v_cruise_kph = clip(self.v_cruise_kph, V_CRUISE_MIN, V_CRUISE_MAX) if not self.enabled and b.type in ["accelCruise", "decelCruise" ] and not b.pressed: enable_request = True # do disable on button down if b.type == "cancel" and b.pressed: self.AM.add("disable", self.enabled) self.prof.checkpoint("Buttons") # *** health checking logic *** hh = messaging.recv_sock(self.health) if hh is not None: # if the board isn't allowing controls but somehow we are enabled! # TODO: this should be in state transition with a function follower logic if not hh.health.controlsAllowed and self.enabled: self.AM.add("controlsMismatch", self.enabled) # disable if the pedals are pressed while engaged, this is a user disable if self.enabled: if self.CS.gasPressed or self.CS.brakePressed or not self.CS.cruiseState.available: self.AM.add("disable", self.enabled) # it can happen that car cruise disables while comma system is enabled: need to # keep braking if needed or if the speed is very low # TODO: for the Acura, cancellation below 25mph is normal. Issue a non loud alert if self.CP.enableCruise and not self.CS.cruiseState.enabled and \ (self.CC.brake <= 0. or self.CS.vEgo < 0.3): self.AM.add("cruiseDisabled", self.enabled) if enable_request: # check for pressed pedals if self.CS.gasPressed or self.CS.brakePressed: self.AM.add("pedalPressed", self.enabled) enable_request = False else: print "enabled pressed at", self.cur_time self.last_enable_request = self.cur_time # don't engage with less than 15% free if self.free_space < 0.15: self.AM.add("outOfSpace", self.enabled) enable_request = False if self.CP.enableCruise: enable_condition = ((self.cur_time - self.last_enable_request) < 0.2) and self.CS.cruiseState.enabled else: enable_condition = enable_request #print "==============" #print enable_condition if self.CP.enableCruise and self.CS.cruiseState.enabled: self.v_cruise_kph = self.CS.cruiseState.speed * CV.MS_TO_KPH self.prof.checkpoint("AdaptiveCruise") # *** what's the plan *** plan_packet = self.PL.update(self.CS, self.LoC) #print "============" #print plan_packet self.plan = plan_packet.plan self.plan_ts = plan_packet.logMonoTime #print "======= Lat Plan" #print self.plan.dPoly # if user is not responsive to awareness alerts, then start a smooth deceleration if self.awareness_status < -0.: self.plan.aTargetMax = min(self.plan.aTargetMax, AWARENESS_DECEL) self.plan.aTargetMin = min(self.plan.aTargetMin, self.plan.aTargetMax) ####### to check the comma control status #print "======== enabled??" #print self.enabled if enable_request or enable_condition or self.enabled: # add all alerts from car for alert in self.CS.errors: self.AM.add(alert, self.enabled) if not self.plan.longitudinalValid: self.AM.add("radarCommIssue", self.enabled) if self.cal_status != Calibration.CALIBRATED: if self.cal_status == Calibration.UNCALIBRATED: self.AM.add("calibrationInProgress", self.enabled, str(self.cal_perc) + '%') else: self.AM.add("calibrationInvalid", self.enabled) if not self.plan.lateralValid: # If the model is not broadcasting, assume that it is because # the user has uploaded insufficient data for calibration. # Other cases that would trigger this are rare and unactionable by the user. self.AM.add("dataNeeded", self.enabled) #print "============ Vision Data Needed============" if self.overtemp: self.AM.add("overheat", self.enabled) # *** angle offset learning *** if self.rk.frame % 5 == 2 and self.plan.lateralValid: # *** run this at 20hz again *** self.angle_offset = learn_angle_offset(self.enabled, self.CS.vEgo, self.angle_offset, self.plan.dPoly, self.LaC.y_des, self.CS.steeringPressed) # *** gas/brake PID loop *** final_gas, final_brake = self.LoC.update( self.enabled, self.CS.vEgo, self.v_cruise_kph, self.plan.vTarget, [self.plan.aTargetMin, self.plan.aTargetMax], self.plan.jerkFactor, self.CP) # *** steering PID loop *** final_steer, sat_flag = self.LaC.update(self.enabled, self.CS.vEgo, self.CS.steeringAngle, self.CS.steeringPressed, self.plan.dPoly, self.angle_offset, self.CP) self.prof.checkpoint("PID") # ***** handle alerts **** # send FCW alert if triggered by planner if self.plan.fcw: self.AM.add("fcw", self.enabled) # send a "steering required alert" if saturation count has reached the limit if sat_flag: self.AM.add("steerSaturated", self.enabled) if self.enabled and self.AM.alertShouldDisable(): print "DISABLING IMMEDIATELY ON ALERT" self.enabled = False if self.enabled and self.AM.alertShouldSoftDisable(): if self.soft_disable_timer is None: self.soft_disable_timer = 3 * self.rate elif self.soft_disable_timer == 0: print "SOFT DISABLING ON ALERT" self.enabled = False else: self.soft_disable_timer -= 1 else: self.soft_disable_timer = None if enable_condition and not self.enabled and not self.AM.alertPresent( ): print "*** enabling controls" # beep for enabling self.AM.add("enable", self.enabled) # enable both lateral and longitudinal controls self.enabled = True # on activation, let's always set v_cruise from where we are, even if PCM ACC is active self.v_cruise_kph = int( round(max(self.CS.vEgo * CV.MS_TO_KPH, V_CRUISE_ENABLE_MIN))) # 6 minutes driver you're on self.awareness_status = 1.0 # reset the PID loops self.LaC.reset() # start long control at actual speed self.LoC.reset(v_pid=self.CS.vEgo) # *** push the alerts to current *** # TODO: remove output, store them inside AM class instead self.alert_text_1, self.alert_text_2, self.visual_alert, self.audible_alert = self.AM.process_alerts( self.cur_time) # ***** control the car ***** self.CC.enabled = self.enabled self.CC.gas = float(final_gas) self.CC.brake = float(final_brake) self.CC.steeringTorque = float(final_steer) self.CC.cruiseControl.override = True # always cancel if we have an interceptor self.CC.cruiseControl.cancel = bool( not self.CP.enableCruise or (not self.enabled and self.CS.cruiseState.enabled)) # brake discount removes a sharp nonlinearity brake_discount = (1.0 - clip(final_brake * 3., 0.0, 1.0)) self.CC.cruiseControl.speedOverride = float( max(0.0, ((self.LoC.v_pid - .5) * brake_discount)) if self.CP.enableCruise else 0.0) #CC.cruiseControl.accelOverride = float(AC.a_pcm) # TODO: fix this self.CC.cruiseControl.accelOverride = float(1.0) self.CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) self.CC.hudControl.speedVisible = self.enabled self.CC.hudControl.lanesVisible = self.enabled self.CC.hudControl.leadVisible = self.plan.hasLead self.CC.hudControl.visualAlert = self.visual_alert self.CC.hudControl.audibleAlert = self.audible_alert # TODO: remove it from here and put it in state_transition # this alert will apply next controls cycle if not self.CI.apply(self.CC): self.AM.add("controlsFailed", self.enabled) def data_send(self): # broadcast carControl first cc_send = messaging.new_message() cc_send.init('carControl') cc_send.carControl = copy(self.CC) self.carcontrol.send(cc_send.to_bytes()) self.prof.checkpoint("CarControl") # broadcast carState cs_send = messaging.new_message() cs_send.init('carState') cs_send.carState = copy(self.CS) self.carstate.send(cs_send.to_bytes()) # ***** publish state to logger ***** # publish controls state at 100Hz dat = messaging.new_message() dat.init('live100') # show rear view camera on phone if in reverse gear or when button is pressed dat.live100.rearViewCam = ( 'reverseGear' in self.CS.errors and self.rear_view_allowed) or self.rear_view_toggle dat.live100.alertText1 = self.alert_text_1 dat.live100.alertText2 = self.alert_text_2 dat.live100.awarenessStatus = max(self.awareness_status, 0.0) if self.enabled else 0.0 # what packets were used to process dat.live100.canMonoTimes = list(self.CS.canMonoTimes) dat.live100.planMonoTime = self.plan_ts # if controls is enabled dat.live100.enabled = self.enabled # car state dat.live100.vEgo = self.CS.vEgo dat.live100.angleSteers = self.CS.steeringAngle dat.live100.steerOverride = self.CS.steeringPressed # longitudinal control state dat.live100.vPid = float(self.LoC.v_pid) dat.live100.vCruise = float(self.v_cruise_kph) dat.live100.upAccelCmd = float(self.LoC.Up_accel_cmd) dat.live100.uiAccelCmd = float(self.LoC.Ui_accel_cmd) # lateral control state dat.live100.yActual = float(self.LaC.y_actual) dat.live100.yDes = float(self.LaC.y_des) dat.live100.upSteer = float(self.LaC.Up_steer) dat.live100.uiSteer = float(self.LaC.Ui_steer) # processed radar state, should add a_pcm? dat.live100.vTargetLead = float(self.plan.vTarget) dat.live100.aTargetMin = float(self.plan.aTargetMin) dat.live100.aTargetMax = float(self.plan.aTargetMax) dat.live100.jerkFactor = float(self.plan.jerkFactor) # log learned angle offset dat.live100.angleOffset = float(self.angle_offset) # lag dat.live100.cumLagMs = -self.rk.remaining * 1000. self.live100.send(dat.to_bytes()) self.prof.checkpoint("Live100") def wait(self): # *** run loop at fixed rate *** if self.rk.keep_time(): self.prof.display()
class Controls: def __init__(self, sm=None, pm=None, can_sock=None): gc.disable() set_realtime_priority(3) # 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: self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', \ 'dMonitoringState', 'plan', 'pathPlan']) 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 health and one CAN packet hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno] print("Waiting for CAN messages...") messaging.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("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" internet_needed = params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0') \ and open('/proc/asound/card0/state').read().strip() == '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 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) put_nonblocking("LongitudinalControl", "1" if self.CP.openpilotLongitudinalControl else "0") 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.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.events_prev = [] self.current_alert_types = [] self.sm['liveCalibration'].calStatus = Calibration.INVALID self.sm['pathPlan'].sensorValid = True self.sm['pathPlan'].posenetValid = True self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False self.startup_event = get_startup_event(car_recognized, controller_available, hw_type) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if internet_needed: self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if self.read_only and not passive: self.events.add(EventName.carUnrecognized, static=True) # if hw_type == HwType.whitePanda: # self.events.add(EventName.whitePandaUnsupported, 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['dMonitoringState'].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['thermal'].batteryPercent < 1 and self.sm[ 'thermal'].chargingError: # at zero percent battery, while discharging, OP should not allowed self.events.add(EventName.lowBattery) if self.sm['thermal'].thermalStatus >= ThermalStatus.red: self.events.add(EventName.overheat) if self.sm['thermal'].freeSpace < 0.07: # under 7% of space free no enable allowed self.events.add(EventName.outOfSpace) if self.sm['thermal'].memUsedPercent > 90: self.events.add(EventName.lowMemory) # 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[ 'pathPlan'].laneChangeState == LaneChangeState.preLaneChange: if self.sm[ 'pathPlan'].laneChangeDirection == LaneChangeDirection.left: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) elif self.sm['pathPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, \ LaneChangeState.laneChangeFinishing]: self.events.add(EventName.laneChange) if self.can_rcv_error: self.events.add(EventName.canError) if self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) if not self.sm.alive['plan'] and self.sm.alive['pathPlan']: # only plan not being received: radar not communicating self.events.add(EventName.radarCommIssue) elif not self.sm.all_alive_and_valid(): self.events.add(EventName.commIssue) if not self.sm['pathPlan'].mpcSolutionValid: self.events.add(EventName.plannerError) if not self.sm['pathPlan'].sensorValid and os.getenv( "NOSENSOR") is None: self.events.add(EventName.sensorDataInvalid) if not self.sm['pathPlan'].paramsValid: self.events.add(EventName.vehicleModelInvalid) if not self.sm['pathPlan'].posenetValid: self.events.add(EventName.posenetInvalid) if not self.sm['plan'].radarValid: self.events.add(EventName.radarFault) if self.sm['plan'].radarCanError: self.events.add(EventName.radarCanError) if not CS.canValid: self.events.add(EventName.canError) if log.HealthData.FaultType.relayMalfunction in self.sm[ 'health'].faults: self.events.add(EventName.relayMalfunction) if self.sm['plan'].fcw: self.events.add(EventName.fcw) # Only allow engagement with brake pressed when stopped behind another stopped car if CS.brakePressed and self.sm['plan'].vTargetFuture >= STARTING_TARGET_SPEED \ and not self.CP.radarOffCan 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['health'].controlsAllowed and self.enabled: self.mismatch_counter += 1 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.enableCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.enabled) elif self.CP.enableCruise 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 # 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""" plan = self.sm['plan'] path_plan = self.sm['pathPlan'] 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) plan_age = DT_CTRL * (self.sm.frame - self.sm.rcv_frame['plan']) # no greater than dt mpc + dt, to prevent too high extraps dt = min(plan_age, LON_MPC_STEP + DT_CTRL) + DT_CTRL a_acc_sol = plan.aStart + (dt / LON_MPC_STEP) * (plan.aTarget - plan.aStart) v_acc_sol = plan.vStart + dt * (a_acc_sol + plan.aStart) / 2.0 # Gas/Brake PID loop actuators.gas, actuators.brake = self.LoC.update( self.active, CS, v_acc_sol, plan.vTargetFuture, a_acc_sol, self.CP) # Steering PID loop and lateral MPC actuators.steer, actuators.steerAngle, lac_log = self.LaC.update( self.active, CS, self.CP, path_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.steerAngle - CS.steeringAngle) > 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): # Check if we deviated from the path left_deviation = actuators.steer > 0 and path_plan.dPoly[3] > 0.1 right_deviation = actuators.steer < 0 and path_plan.dPoly[3] < -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 = not self.CP.enableCruise or ( 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['plan'].aTarget, CS.vEgo, self.sm['plan'].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['plan'].hasLead right_lane_visible = self.sm['pathPlan'].rProb > 0.5 left_lane_visible = self.sm['pathPlan'].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['model'].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['pathPlan'].lPoly[3] < (1.08 - CAMERA_OFFSET)) r_lane_close = right_lane_visible and (self.sm['pathPlan'].rPoly[3] > -(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) 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) CC.hudControl.visualAlert = self.AM.visual_alert if not self.read_only: # 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['dMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) steer_angle_rad = (CS.steeringAngle - self.sm['pathPlan'].angleOffset) * CV.DEG_TO_RAD # 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.driverMonitoringOn = self.sm[ 'dMonitoringState'].faceDetected controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.planMonoTime = self.sm.logMonoTime['plan'] controlsState.pathPlanMonoTime = self.sm.logMonoTime['pathPlan'] controlsState.enabled = self.enabled controlsState.active = self.active controlsState.vEgo = CS.vEgo controlsState.vEgoRaw = CS.vEgoRaw controlsState.angleSteers = CS.steeringAngle controlsState.curvature = self.VM.calc_curvature( steer_angle_rad, CS.vEgo) controlsState.steerOverride = CS.steeringPressed 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.angleSteersDes = float(self.LaC.angle_steers_des) controlsState.vTargetLead = float(v_acc) controlsState.aTarget = float(a_acc) controlsState.jerkFactor = float(self.sm['plan'].jerkFactor) controlsState.gpsPlannerActive = self.sm['plan'].gpsPlannerActive controlsState.vCurvature = self.sm['plan'].vCurvature controlsState.decelForModel = self.sm[ 'plan'].longitudinalPlanSource == LongitudinalPlanSource.model controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.mapValid = self.sm['plan'].mapValid controlsState.forceDecel = bool(force_decel) controlsState.canErrorCounter = self.can_error_counter if 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()
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', 'peripheralState', '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.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, self.CI) 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.button_timers = { ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0 } # 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 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 EON 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) 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 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) planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled model_fcw = self.sm[ 'modelV2'].meta.hardBrakePredicted and not CS.brakePressed if planner_fcw or model_fcw: 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 >= 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) all_valid = CS.canValid and self.sm.all_alive_and_valid() if not self.initialized and (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 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.button_timers, self.enabled, self.is_metric) 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() 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 self.active: self.LaC.reset() 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) actuators.accel = self.LoC.update(self.active, CS, self.CP, long_plan, pid_accel_limits) # 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: actuators.accel = 4.0 * clip(self.sm['testJoystick'].axes[0], -1, 1) 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) # 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 actuators, lac_log def update_button_timers(self, buttonEvents): # increment timer for buttons still pressed for k in self.button_timers.keys(): 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, 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.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 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") self.update_button_timers(CS.buttonEvents) def controlsd_thread(self): while True: self.step() self.rk.monitor_time() self.prof.display()
def __init__(self, sm=None, pm=None, can_sock=None): gc.disable() set_realtime_priority(3) # 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: self.sm = messaging.SubMaster(['thermal', 'health', 'model', 'liveCalibration', \ 'dMonitoringState', 'plan', 'pathPlan']) 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 health and one CAN packet hw_type = messaging.recv_one(self.sm.sock['health']).health.hwType has_relay = hw_type in [HwType.blackPanda, HwType.uno] print("Waiting for CAN messages...") messaging.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("IsMetric", encoding='utf8') == "1" self.is_ldw_enabled = params.get("IsLdwEnabled", encoding='utf8') == "1" internet_needed = params.get("Offroad_ConnectivityNeeded", encoding='utf8') is not None community_feature_toggle = params.get("CommunityFeaturesToggle", encoding='utf8') == "1" openpilot_enabled_toggle = params.get("OpenpilotEnabledToggle", encoding='utf8') == "1" passive = params.get("Passive", encoding='utf8') == "1" or \ internet_needed or not openpilot_enabled_toggle # detect sound card presence and ensure successful init sounds_available = not os.path.isfile('/EON') or (os.path.isdir('/proc/asound/card0') \ and open('/proc/asound/card0/state').read().strip() == '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 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) put_nonblocking("LongitudinalControl", "1" if self.CP.openpilotLongitudinalControl else "0") 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.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.events_prev = [] self.current_alert_types = [] self.sm['liveCalibration'].calStatus = Calibration.INVALID self.sm['pathPlan'].sensorValid = True self.sm['pathPlan'].posenetValid = True self.sm['thermal'].freeSpace = 1. self.sm['dMonitoringState'].events = [] self.sm['dMonitoringState'].awarenessStatus = 1. self.sm['dMonitoringState'].faceDetected = False self.startup_event = get_startup_event(car_recognized, controller_available, hw_type) if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) if internet_needed: self.events.add(EventName.internetConnectivityNeeded, static=True) if community_feature_disallowed: self.events.add(EventName.communityFeatureDisallowed, static=True) if self.read_only and not passive: self.events.add(EventName.carUnrecognized, static=True) # if hw_type == HwType.whitePanda: # self.events.add(EventName.whitePandaUnsupported, 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 __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.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, ignore_avg_freq=['radarState']) 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 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 params = Params() self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") self.enable_lte_onroad = params.get_bool("EnableLteOnroad") 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' fuzzy_fingerprint = self.CP.fuzzyFingerprint # 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 = self.CP.communityFeature or fuzzy_fingerprint 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 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 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, fuzzy_fingerprint) 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 controlsd_thread(gctx=None, rate=100): gc.disable() # start the loop set_realtime_priority(3) ##### AS context = zmq.Context() live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) carla_socket = context.socket(zmq.PAIR) carla_socket.bind("tcp://*:5560") is_metric = True passive = True ##### AS # No sendcan if passive if not passive: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) else: sendcan = None # Sub sockets poller = zmq.Poller() #thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) #health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) #driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) plan_sock = messaging.sub_sock(context, service_list['plan'].port, conflate=True, poller=poller) path_plan_sock = messaging.sub_sock(context, service_list['pathPlan'].port, conflate=True, poller=poller) #logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CP = ToyotaInterface.get_params("TOYOTA PRIUS 2017", {}) CP.steerRatio = 1.0 CI = ToyotaInterface(CP, sendcan) if CI is None: raise Exception("unsupported car") # if stock camera is connected, then force passive behavior if not CP.enableCamera: passive = True sendcan = None if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(CP) AM = AlertManager() if not passive: AM.add("startup", False) state = State.enabled soft_disable_timer = 0 v_cruise_kph = 50 ##### !!! change v_cruise_kph_last = 0 ##### !! change cal_status = Calibration.INVALID cal_perc = 0 plan = messaging.new_message() plan.init('plan') path_plan = messaging.new_message() path_plan.init('pathPlan') rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) angle_offset = 0. prof = Profiler(False) # off by default startup = True ##### AS while True: start_time = int(sec_since_boot() * 1e9) prof.checkpoint("Ratekeeper", ignore=True) # Sample data and compute car events CS, events, cal_status, cal_perc, plan, path_plan =\ data_sample(CI, CC, plan_sock, path_plan_sock, cal, poller, cal_status, cal_perc, state, plan, path_plan, v_cruise_kph) prof.checkpoint("Sample") ##### AS since we dont do preenabled state if startup: LaC.reset() LoC.reset(v_pid=CS.vEgo) if cal_status != Calibration.CALIBRATED: continue startup = False path_plan_age = (start_time - path_plan.logMonoTime) / 1e9 plan_age = (start_time - plan.logMonoTime) / 1e9 if not path_plan.pathPlan.valid or plan_age > 0.5 or path_plan_age > 0.5: print 'planner time too long' #events.append(create_event('plannerError', [ET.NO_ENTRY, ET.SOFT_DISABLE])) events += list(plan.plan.events) # Only allow engagement with brake pressed when stopped behind another stopped car #if CS.brakePressed and plan.plan.vTargetFuture >= STARTING_TARGET_SPEED and not CP.radarOffCan and CS.vEgo < 0.3: # events.append(create_event('noTarget', [ET.NO_ENTRY, ET.IMMEDIATE_DISABLE])) if not passive: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # Compute actuators (runs PID loops and lateral MPC) actuators, v_cruise_kph, angle_offset, v_acc, a_acc = \ state_control(plan.plan, path_plan.pathPlan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc) prof.checkpoint("State Control") # Publish data CC = data_send(plan, path_plan, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, AM, LaC, LoC, angle_offset, passive, start_time, v_acc, a_acc, carla_socket) prof.checkpoint("Sent") rk.keep_time() # Run at 100Hz, no 20 Hz prof.display()
def controlsd_thread(gctx=None, rate=100, default_bias=0.): gc.disable() # start the loop set_realtime_priority(3) context = zmq.Context() params = Params() # pub live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) livempc = messaging.pub_sock(context, service_list['liveMpc'].port) is_metric = params.get("IsMetric") == "1" passive = params.get("Passive") != "0" if not passive: while 1: try: sendcan = messaging.pub_sock(context, service_list['sendcan'].port) break except zmq.error.ZMQError: kill_defaultd() else: sendcan = None # sub poller = zmq.Poller() thermal = messaging.sub_sock(context, service_list['thermal'].port, conflate=True, poller=poller) health = messaging.sub_sock(context, service_list['health'].port, conflate=True, poller=poller) cal = messaging.sub_sock(context, service_list['liveCalibration'].port, conflate=True, poller=poller) driver_monitor = messaging.sub_sock(context, service_list['driverMonitoring'].port, conflate=True, poller=poller) gps_location = messaging.sub_sock(context, service_list['gpsLocationExternal'].port, conflate=True, poller=poller) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan, 1.0 if passive else None) if CI is None: raise Exception("unsupported car") # if stock camera is connected, then force passive behavior if not CP.enableCamera: passive = True sendcan = None if passive: CP.safetyModel = car.CarParams.SafetyModels.noOutput fcw_enabled = params.get("IsFcwEnabled") == "1" geofence = None PL = Planner(CP, fcw_enabled) LoC = LongControl(CP, CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(VM) AM = AlertManager() driver_status = DriverStatus() if not passive: AM.add("startup", False) # write CarParams params.put("CarParams", CP.to_bytes()) state = State.disabled soft_disable_timer = 0 v_cruise_kph = 255 v_cruise_kph_last = 0 overtemp = False free_space = False cal_status = Calibration.INVALID cal_perc = 0 mismatch_counter = 0 low_battery = False rk = Ratekeeper(rate, print_delay_threshold=2./1000) # learned angle offset angle_offset = default_bias calibration_params = params.get("CalibrationParams") if calibration_params: try: calibration_params = json.loads(calibration_params) angle_offset = calibration_params["angle_offset2"] except (ValueError, KeyError): pass prof = Profiler(False) # off by default while 1: prof.checkpoint("Ratekeeper", ignore=True) # sample data and compute car events CS, events, cal_status, cal_perc, overtemp, free_space, low_battery, mismatch_counter = data_sample(CI, CC, thermal, cal, health, driver_monitor, gps_location, poller, cal_status, cal_perc, overtemp, free_space, low_battery, driver_status, geofence, state, mismatch_counter, params) prof.checkpoint("Sample") # define plan plan, plan_ts = calc_plan(CS, CP, events, PL, LaC, LoC, v_cruise_kph, driver_status, geofence) prof.checkpoint("Plan") if not passive: # update control state state, soft_disable_timer, v_cruise_kph, v_cruise_kph_last = \ state_transition(CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # compute actuators actuators, v_cruise_kph, driver_status, angle_offset = state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last, AM, rk, driver_status, PL, LaC, LoC, VM, angle_offset, passive, is_metric, cal_perc) prof.checkpoint("State Control") # publish data CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive) prof.checkpoint("Sent") # *** run loop at fixed rate *** rk.keep_time() prof.display()
def controlsd_thread(gctx, rate=100): # start the loop set_realtime_priority(2) context = zmq.Context() # pub live100 = messaging.pub_sock(context, service_list['live100'].port) carstate = messaging.pub_sock(context, service_list['carState'].port) carcontrol = messaging.pub_sock(context, service_list['carControl'].port) sendcan = messaging.pub_sock(context, service_list['sendcan'].port) livempc = messaging.pub_sock(context, service_list['liveMpc'].port) # sub thermal = messaging.sub_sock(context, service_list['thermal'].port) health = messaging.sub_sock(context, service_list['health'].port) cal = messaging.sub_sock(context, service_list['liveCalibration'].port) logcan = messaging.sub_sock(context, service_list['can'].port) CC = car.CarControl.new_message() CI, CP = get_car(logcan, sendcan) PL = Planner(CP) LoC = LongControl(CI.compute_gb) VM = VehicleModel(CP) LaC = LatControl(VM) AM = AlertManager() # write CarParams params = Params() params.put("CarParams", CP.to_bytes()) state = State.DISABLED soft_disable_timer = 0 v_cruise_kph = 255 overtemp = False free_space = False cal_status = Calibration.UNCALIBRATED rear_view_toggle = False rear_view_allowed = params.get("IsRearViewMirror") == "1" # 0.0 - 1.0 awareness_status = 0. rk = Ratekeeper(rate, print_delay_threshold=2. / 1000) # learned angle offset angle_offset = 0. calibration_params = params.get("CalibrationParams") if calibration_params: try: calibration_params = json.loads(calibration_params) angle_offset = calibration_params["angle_offset"] except (ValueError, KeyError): pass prof = Profiler() while 1: prof.reset() # avoid memory leak # sample data and compute car events CS, events, cal_status, overtemp, free_space = data_sample( CI, CC, thermal, health, cal, cal_status, overtemp, free_space) prof.checkpoint("Sample") # define plan plan, plan_ts = calc_plan(CS, events, PL, LoC) prof.checkpoint("Plan") # update control state state, soft_disable_timer, v_cruise_kph = state_transition( CS, CP, state, events, soft_disable_timer, v_cruise_kph, AM) prof.checkpoint("State transition") # compute actuators actuators, v_cruise_kph, awareness_status, angle_offset, rear_view_toggle = state_control( plan, CS, CP, state, events, v_cruise_kph, AM, rk, awareness_status, PL, LaC, LoC, VM, angle_offset, rear_view_allowed, rear_view_toggle) prof.checkpoint("State Control") # publish data CC = data_send(plan, plan_ts, CS, CI, CP, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol, live100, livempc, AM, rear_view_allowed, rear_view_toggle, awareness_status, LaC, LoC, angle_offset) prof.checkpoint("Sent") # *** run loop at fixed rate *** if rk.keep_time(): prof.display()