def plannerd_thread(): gc.disable() # start the loop set_realtime_priority(2) params = Params() # Get FCW toggle from settings fcw_enabled = params.get("IsFcwEnabled") == "1" cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP, fcw_enabled) PP = PathPlanner(CP) VM = VehicleModel(CP) sm = messaging.SubMaster( ['carState', 'controlsState', 'radarState', 'model', 'liveParameters']) sm['liveParameters'].valid = True sm['liveParameters'].sensorValid = True sm['liveParameters'].steerRatio = CP.steerRatio sm['liveParameters'].stiffnessFactor = 1.0 while True: sm.update() if sm.updated['model']: PP.update(sm, CP, VM) if sm.updated['radarState']: PL.update(sm, CP, VM, PP)
def plannerd_thread(sm=None, pm=None): config_realtime_process(2, Priority.CTRL_LOW) cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP) PP = PathPlanner(CP) VM = VehicleModel(CP) if sm is None: sm = messaging.SubMaster(['carState', 'controlsState', 'radarState', 'model', 'liveParameters', 'modelLongButton'], poll=['radarState', 'model']) if pm is None: pm = messaging.PubMaster(['plan', 'liveLongitudinalMpc', 'pathPlan', 'liveMpc']) sm['liveParameters'].valid = True sm['liveParameters'].sensorValid = True sm['liveParameters'].steerRatio = CP.steerRatio sm['liveParameters'].stiffnessFactor = 1.0 while True: sm.update() if sm.updated['model']: PP.update(sm, pm, CP, VM) if sm.updated['radarState']: PL.update(sm, pm, CP, VM, PP)
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 plannerd_thread(): context = zmq.Context() params = Params() # Get FCW toggle from settings fcw_enabled = params.get("IsFcwEnabled") == "1" cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP, fcw_enabled) PP = PathPlanner(CP) VM = VehicleModel(CP) poller = zmq.Poller() car_state_sock = messaging.sub_sock(context, service_list['carState'].port, conflate=True, poller=poller) live100_sock = messaging.sub_sock(context, service_list['live100'].port, conflate=True, poller=poller) live20_sock = messaging.sub_sock(context, service_list['live20'].port, conflate=True, poller=poller) model_sock = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=poller) live_map_data_sock = messaging.sub_sock(context, service_list['liveMapData'].port, conflate=True, poller=poller) live_parameters_sock = messaging.sub_sock(context, service_list['liveParameters'].port, conflate=True, poller=poller) car_state = messaging.new_message() car_state.init('carState') live100 = messaging.new_message() live100.init('live100') model = messaging.new_message() model.init('model') live20 = messaging.new_message() live20.init('live20') live_map_data = messaging.new_message() live_map_data.init('liveMapData') live_parameters = messaging.new_message() live_parameters.init('liveParameters') live_parameters.liveParameters.valid = True live_parameters.liveParameters.steerRatio = CP.steerRatio live_parameters.liveParameters.stiffnessFactor = 1.0 while True: for socket, event in poller.poll(): if socket is live100_sock: live100 = messaging.recv_one(socket) elif socket is car_state_sock: car_state = messaging.recv_one(socket) elif socket is live_parameters_sock: live_parameters = messaging.recv_one(socket) elif socket is model_sock: model = messaging.recv_one(socket) PP.update(CP, VM, car_state, model, live100, live_parameters) elif socket is live_map_data_sock: live_map_data = messaging.recv_one(socket) elif socket is live20_sock: live20 = messaging.recv_one(socket) PL.update(car_state, CP, VM, PP, live20, live100, model, live_map_data)
def plannerd_thread(sm=None, pm=None, arne_sm=None): gc.disable() # start the loop set_realtime_priority(52) cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP) PP = PathPlanner(CP) VM = VehicleModel(CP) if sm is None: sm = messaging.SubMaster([ 'carState', 'controlsState', 'radarState', 'model', 'liveParameters', 'liveMapData' ]) if arne_sm is None: arne_sm = messaging_arne.SubMaster( ['arne182Status', 'latControl', 'modelLongButton']) if pm is None: pm = messaging.PubMaster( ['plan', 'liveLongitudinalMpc', 'pathPlan', 'liveMpc']) sm['liveParameters'].valid = True sm['liveParameters'].sensorValid = True sm['liveParameters'].steerRatio = CP.steerRatio sm['liveParameters'].stiffnessFactor = 1.0 while True: sm.update() arne_sm.update(0) if sm.updated['model']: PP.update(sm, pm, CP, VM) if sm.updated['radarState']: PL.update(sm, pm, CP, VM, PP, arne_sm)
def plannerd_thread(sm=None, pm=None): gc.disable() # start the loop set_realtime_priority(52) cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP) PP = PathPlanner(CP) VM = VehicleModel(CP) if sm is None: sm = messaging.SubMaster([ 'carState', 'controlsState', 'radarState', 'model', 'liveParameters', 'dragonConf' ]) if pm is None: pm = messaging.PubMaster( ['plan', 'liveLongitudinalMpc', 'pathPlan', 'liveMpc']) sm['liveParameters'].valid = True sm['liveParameters'].sensorValid = True sm['liveParameters'].steerRatio = CP.steerRatio sm['liveParameters'].stiffnessFactor = 1.0 sm['dragonConf'].dpSlowOnCurve = False sm['dragonConf'].dpAccelProfile = 0 while True: sm.update() if sm.updated['model']: PP.update(sm, pm, CP, VM) if sm.updated['radarState']: PL.update(sm, pm, CP, VM, PP)
def controlsd_thread(gctx, rate=100): # start the loop set_realtime_priority(2) 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 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, 1.0 if passive else None) if CI is None: if passive: return else: 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. 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() 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, v_cruise_kph, awareness_status) prof.checkpoint("Plan") if not passive: # 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, passive) prof.checkpoint("Sent") # *** run loop at fixed rate *** if rk.keep_time(): 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()
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) 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 # 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) 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) 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()
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()
def plannerd_thread(): gc.disable() # start the loop set_realtime_priority(2) context = zmq.Context() params = Params() # Get FCW toggle from settings fcw_enabled = params.get("IsFcwEnabled") == "1" cloudlog.info("plannerd is waiting for CarParams") CP = car.CarParams.from_bytes(Params().get("CarParams", block=True)) cloudlog.info("plannerd got CarParams: %s", CP.carName) PL = Planner(CP, fcw_enabled) PP = PathPlanner(CP) VM = VehicleModel(CP) poller = zmq.Poller() car_state_sock = messaging.sub_sock(context, service_list['carState'].port, conflate=True, poller=poller) controls_state_sock = messaging.sub_sock(context, service_list['controlsState'].port, conflate=True, poller=poller) radar_state_sock = messaging.sub_sock(context, service_list['radarState'].port, conflate=True, poller=poller) model_sock = messaging.sub_sock(context, service_list['model'].port, conflate=True, poller=poller) live_parameters_sock = messaging.sub_sock(context, service_list['liveParameters'].port, conflate=True, poller=poller) # live_map_data_sock = messaging.sub_sock(context, service_list['liveMapData'].port, conflate=True, poller=poller) car_state = messaging.new_message() car_state.init('carState') controls_state = messaging.new_message() controls_state.init('controlsState') model = messaging.new_message() model.init('model') radar_state = messaging.new_message() radar_state.init('radarState') live_map_data = messaging.new_message() live_map_data.init('liveMapData') live_parameters = messaging.new_message() live_parameters.init('liveParameters') live_parameters.liveParameters.valid = True live_parameters.liveParameters.sensorValid = True live_parameters.liveParameters.steerRatio = CP.steerRatio live_parameters.liveParameters.stiffnessFactor = 1.0 rcv_times = defaultdict(int) while True: for socket, event in poller.poll(): msg = messaging.recv_one(socket) rcv_times[msg.which()] = sec_since_boot() if socket is controls_state_sock: controls_state = msg elif socket is car_state_sock: car_state = msg elif socket is live_parameters_sock: live_parameters = msg elif socket is model_sock: model = msg PP.update(rcv_times, CP, VM, car_state, model, controls_state, live_parameters) elif socket is radar_state_sock: radar_state = msg PL.update(rcv_times, car_state, CP, VM, PP, radar_state, controls_state, model, live_map_data)