Merge remote-tracking branch 'origin/master' into enable-online-lag

enable-online-lag
Kacper Rączy 1 week ago
commit 1aaf04b6bd
  1. 20
      selfdrive/controls/lib/longitudinal_planner.py
  2. 10
      selfdrive/modeld/fill_model_msg.py
  3. 7
      selfdrive/modeld/modeld.py
  4. 4
      selfdrive/modeld/models/driving_policy.onnx
  5. 4
      selfdrive/modeld/models/driving_vision.onnx
  6. 13
      selfdrive/modeld/parse_model_outputs.py
  7. 1
      selfdrive/test/longitudinal_maneuvers/plant.py
  8. 4
      selfdrive/test/process_replay/migration.py
  9. 2
      selfdrive/test/process_replay/ref_commit
  10. 156
      selfdrive/ui/translations/main_de.ts
  11. 3
      system/camerad/cameras/camera_common.cc
  12. 2
      system/camerad/cameras/camera_common.h
  13. 10
      system/camerad/cameras/camera_qcom2.cc
  14. 18
      system/camerad/cameras/ife.h
  15. 40
      system/camerad/cameras/spectra.cc
  16. 11
      system/camerad/sensors/os04c10.cc
  17. 54
      system/camerad/sensors/os04c10_registers.h
  18. 2
      system/camerad/sensors/sensor.h

@ -89,14 +89,15 @@ class LongitudinalPlanner:
return x, v, a, j, throttle_prob return x, v, a, j, throttle_prob
def update(self, sm): def update(self, sm):
self.mpc.mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' self.mpc.mode = 'acc'
self.mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc'
if len(sm['carControl'].orientationNED) == 3: if len(sm['carControl'].orientationNED) == 3:
accel_coast = get_coast_accel(sm['carControl'].orientationNED[1]) accel_coast = get_coast_accel(sm['carControl'].orientationNED[1])
else: else:
accel_coast = ACCEL_MAX accel_coast = ACCEL_MAX
v_ego = sm['carState'].vEgo v_ego = sm['modelV2'].velocity.x[0]
v_cruise_kph = min(sm['carState'].vCruise, V_CRUISE_MAX) v_cruise_kph = min(sm['carState'].vCruise, V_CRUISE_MAX)
v_cruise = v_cruise_kph * CV.KPH_TO_MS v_cruise = v_cruise_kph * CV.KPH_TO_MS
v_cruise_initialized = sm['carState'].vCruise != V_CRUISE_UNSET v_cruise_initialized = sm['carState'].vCruise != V_CRUISE_UNSET
@ -112,7 +113,7 @@ class LongitudinalPlanner:
# No change cost when user is controlling the speed, or when standstill # No change cost when user is controlling the speed, or when standstill
prev_accel_constraint = not (reset_state or sm['carState'].standstill) prev_accel_constraint = not (reset_state or sm['carState'].standstill)
if self.mpc.mode == 'acc': if self.mode == 'acc':
accel_clip = [ACCEL_MIN, get_max_accel(v_ego)] accel_clip = [ACCEL_MIN, get_max_accel(v_ego)]
steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg
accel_clip = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_clip, self.CP) accel_clip = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_clip, self.CP)
@ -128,7 +129,7 @@ class LongitudinalPlanner:
self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego)) self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego))
# Compute model v_ego error # Compute model v_ego error
self.v_model_error = get_speed_error(sm['modelV2'], v_ego) self.v_model_error = get_speed_error(sm['modelV2'], v_ego)
x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'], self.v_model_error) x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'], 0)
# Don't clip at low speeds since throttle_prob doesn't account for creep # Don't clip at low speeds since throttle_prob doesn't account for creep
self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED
@ -159,8 +160,17 @@ class LongitudinalPlanner:
self.v_desired_filter.x = self.v_desired_filter.x + self.dt * (self.a_desired + a_prev) / 2.0 self.v_desired_filter.x = self.v_desired_filter.x + self.dt * (self.a_desired + a_prev) / 2.0
action_t = self.CP.longitudinalActuatorDelay + DT_MDL action_t = self.CP.longitudinalActuatorDelay + DT_MDL
output_a_target, self.output_should_stop = get_accel_from_plan(self.v_desired_trajectory, self.a_desired_trajectory, CONTROL_N_T_IDX, output_a_target_mpc, output_should_stop_mpc = get_accel_from_plan(self.v_desired_trajectory, self.a_desired_trajectory, CONTROL_N_T_IDX,
action_t=action_t, vEgoStopping=self.CP.vEgoStopping) action_t=action_t, vEgoStopping=self.CP.vEgoStopping)
output_a_target_e2e = sm['modelV2'].action.desiredAcceleration
output_should_stop_e2e = sm['modelV2'].action.shouldStop
if self.mode == 'acc':
output_a_target = output_a_target_mpc
self.output_should_stop = output_should_stop_mpc
else:
output_a_target = min(output_a_target_mpc, output_a_target_e2e)
self.output_should_stop = output_should_stop_e2e or output_should_stop_mpc
for idx in range(2): for idx in range(2):
accel_clip[idx] = np.clip(accel_clip[idx], self.prev_accel_clip[idx] - 0.05, self.prev_accel_clip[idx] + 0.05) accel_clip[idx] = np.clip(accel_clip[idx], self.prev_accel_clip[idx] - 0.05, self.prev_accel_clip[idx] + 0.05)

@ -90,11 +90,11 @@ def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._D
fill_xyzt(modelV2.orientationRate, ModelConstants.T_IDXS, *net_output_data['plan'][0,:,Plan.ORIENTATION_RATE].T) fill_xyzt(modelV2.orientationRate, ModelConstants.T_IDXS, *net_output_data['plan'][0,:,Plan.ORIENTATION_RATE].T)
# temporal pose # temporal pose
temporal_pose = modelV2.temporalPose #temporal_pose = modelV2.temporalPose
temporal_pose.trans = net_output_data['sim_pose'][0,:ModelConstants.POSE_WIDTH//2].tolist() #temporal_pose.trans = net_output_data['sim_pose'][0,:ModelConstants.POSE_WIDTH//2].tolist()
temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:ModelConstants.POSE_WIDTH//2].tolist() #temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:ModelConstants.POSE_WIDTH//2].tolist()
temporal_pose.rot = net_output_data['sim_pose'][0,ModelConstants.POSE_WIDTH//2:].tolist() #temporal_pose.rot = net_output_data['sim_pose'][0,ModelConstants.POSE_WIDTH//2:].tolist()
temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,ModelConstants.POSE_WIDTH//2:].tolist() #temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,ModelConstants.POSE_WIDTH//2:].tolist()
# poly path # poly path
fill_xyz_poly(driving_model_data.path, ModelConstants.POLY_PATH_DEGREE, *net_output_data['plan'][0,:,Plan.POSITION].T) fill_xyz_poly(driving_model_data.path, ModelConstants.POLY_PATH_DEGREE, *net_output_data['plan'][0,:,Plan.POSITION].T)

@ -43,8 +43,8 @@ POLICY_PKL_PATH = Path(__file__).parent / 'models/driving_policy_tinygrad.pkl'
VISION_METADATA_PATH = Path(__file__).parent / 'models/driving_vision_metadata.pkl' VISION_METADATA_PATH = Path(__file__).parent / 'models/driving_vision_metadata.pkl'
POLICY_METADATA_PATH = Path(__file__).parent / 'models/driving_policy_metadata.pkl' POLICY_METADATA_PATH = Path(__file__).parent / 'models/driving_policy_metadata.pkl'
LAT_SMOOTH_SECONDS = 0.0 LAT_SMOOTH_SECONDS = 0.3
LONG_SMOOTH_SECONDS = 0.0 LONG_SMOOTH_SECONDS = 0.3
def smooth_value(val, prev_val, tau): def smooth_value(val, prev_val, tau):
alpha = 1 - np.exp(-DT_MDL / tau) if tau > 0 else 1 alpha = 1 - np.exp(-DT_MDL / tau) if tau > 0 else 1
@ -174,7 +174,7 @@ class ModelState:
# TODO model only uses last value now # TODO model only uses last value now
self.full_prev_desired_curv[0,:-1] = self.full_prev_desired_curv[0,1:] self.full_prev_desired_curv[0,:-1] = self.full_prev_desired_curv[0,1:]
self.full_prev_desired_curv[0,-1,:] = policy_outputs_dict['desired_curvature'][0, :] self.full_prev_desired_curv[0,-1,:] = policy_outputs_dict['desired_curvature'][0, :]
self.numpy_inputs['prev_desired_curv'][:] = self.full_prev_desired_curv[0, self.temporal_idxs] self.numpy_inputs['prev_desired_curv'][:] = 0*self.full_prev_desired_curv[0, self.temporal_idxs]
combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict} combined_outputs_dict = {**vision_outputs_dict, **policy_outputs_dict}
if SEND_RAW_PRED: if SEND_RAW_PRED:
@ -338,6 +338,7 @@ def main(demo=False):
posenet_send = messaging.new_message('cameraOdometry') posenet_send = messaging.new_message('cameraOdometry')
action = get_action_from_model(model_output, prev_action, lat_delay + DT_MDL, long_delay + DT_MDL) action = get_action_from_model(model_output, prev_action, lat_delay + DT_MDL, long_delay + DT_MDL)
prev_action = action
fill_model_msg(drivingdata_send, modelv2_send, model_output, action, fill_model_msg(drivingdata_send, modelv2_send, model_output, action,
publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id,
frame_drop_ratio, meta_main.timestamp_eof, model_execution_time, live_calib_seen) frame_drop_ratio, meta_main.timestamp_eof, model_execution_time, live_calib_seen)

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:98f0121ccb6f850077b04cc91bd33d370fc6cbdc2bd35f1ab55628a15a813f36 oid sha256:fa00a07a4307b0f1638a10ec33b651d8a102e38371289b744f43215c89dfd342
size 15966721 size 15578328

@ -1,3 +1,3 @@
version https://git-lfs.github.com/spec/v1 version https://git-lfs.github.com/spec/v1
oid sha256:897f80d0388250f99bba69b6a8434560cc0fd83157cbeb0bc134c67fe4e64624 oid sha256:f222d2c528f1763828de01bb55e8979b1e4056e1dbb41350f521d2d2bb09d177
size 34882971 size 46265585

@ -88,6 +88,12 @@ class Parser:
self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,)) self.parse_mdn('wide_from_device_euler', outs, in_N=0, out_N=0, out_shape=(ModelConstants.WIDE_FROM_DEVICE_WIDTH,))
self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('lane_lines', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_LANE_LINES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION,
out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH))
for k in ['lead_prob', 'lane_lines_prob']:
self.parse_binary_crossentropy(k, outs)
self.parse_categorical_crossentropy('desire_pred', outs, out_shape=(ModelConstants.DESIRE_PRED_LEN,ModelConstants.DESIRE_PRED_WIDTH)) self.parse_categorical_crossentropy('desire_pred', outs, out_shape=(ModelConstants.DESIRE_PRED_LEN,ModelConstants.DESIRE_PRED_WIDTH))
self.parse_binary_crossentropy('meta', outs) self.parse_binary_crossentropy('meta', outs)
return outs return outs
@ -95,17 +101,10 @@ class Parser:
def parse_policy_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]: def parse_policy_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]:
self.parse_mdn('plan', outs, in_N=ModelConstants.PLAN_MHP_N, out_N=ModelConstants.PLAN_MHP_SELECTION, self.parse_mdn('plan', outs, in_N=ModelConstants.PLAN_MHP_N, out_N=ModelConstants.PLAN_MHP_SELECTION,
out_shape=(ModelConstants.IDX_N,ModelConstants.PLAN_WIDTH)) out_shape=(ModelConstants.IDX_N,ModelConstants.PLAN_WIDTH))
self.parse_mdn('lane_lines', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_LANE_LINES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH))
self.parse_mdn('sim_pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,))
self.parse_mdn('lead', outs, in_N=ModelConstants.LEAD_MHP_N, out_N=ModelConstants.LEAD_MHP_SELECTION,
out_shape=(ModelConstants.LEAD_TRAJ_LEN,ModelConstants.LEAD_WIDTH))
if 'lat_planner_solution' in outs: if 'lat_planner_solution' in outs:
self.parse_mdn('lat_planner_solution', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N,ModelConstants.LAT_PLANNER_SOLUTION_WIDTH)) self.parse_mdn('lat_planner_solution', outs, in_N=0, out_N=0, out_shape=(ModelConstants.IDX_N,ModelConstants.LAT_PLANNER_SOLUTION_WIDTH))
if 'desired_curvature' in outs: if 'desired_curvature' in outs:
self.parse_mdn('desired_curvature', outs, in_N=0, out_N=0, out_shape=(ModelConstants.DESIRED_CURV_WIDTH,)) self.parse_mdn('desired_curvature', outs, in_N=0, out_N=0, out_shape=(ModelConstants.DESIRED_CURV_WIDTH,))
for k in ['lead_prob', 'lane_lines_prob']:
self.parse_binary_crossentropy(k, outs)
self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,)) self.parse_categorical_crossentropy('desire_state', outs, out_shape=(ModelConstants.DESIRE_PRED_WIDTH,))
return outs return outs

@ -107,6 +107,7 @@ class Plant:
position = log.XYZTData.new_message() position = log.XYZTData.new_message()
position.x = [float(x) for x in (self.speed + 0.5) * np.array(ModelConstants.T_IDXS)] position.x = [float(x) for x in (self.speed + 0.5) * np.array(ModelConstants.T_IDXS)]
model.modelV2.position = position model.modelV2.position = position
model.modelV2.action.desiredAcceleration = float(self.acceleration + 0.1)
velocity = log.XYZTData.new_message() velocity = log.XYZTData.new_message()
velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)] velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)]
velocity.x[0] = float(self.speed) # always start at current speed velocity.x[0] = float(self.speed) # always start at current speed

@ -13,7 +13,7 @@ from opendbc.car.gm.values import GMSafetyFlags
from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.modeld.constants import ModelConstants
from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta
from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index
from openpilot.selfdrive.controls.lib.longitudinal_planner import get_accel_from_plan from openpilot.selfdrive.controls.lib.longitudinal_planner import get_accel_from_plan, CONTROL_N_T_IDX
from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.process_config import managed_processes
from openpilot.tools.lib.logreader import LogIterable from openpilot.tools.lib.logreader import LogIterable
@ -109,7 +109,7 @@ def migrate_longitudinalPlan(msgs):
if msg.which() != 'longitudinalPlan': if msg.which() != 'longitudinalPlan':
continue continue
new_msg = msg.as_builder() new_msg = msg.as_builder()
a_target, should_stop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels) a_target, should_stop = get_accel_from_plan(msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels, CONTROL_N_T_IDX)
new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = float(a_target), bool(should_stop) new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = float(a_target), bool(should_stop)
ops.append((index, new_msg.as_reader())) ops.append((index, new_msg.as_reader()))
return ops, [], [] return ops, [], []

@ -1 +1 @@
3d3f875dc211ab0ca8a8e564ecf6dd3f52fcf7d9 0800e73b5d9c801f161b9559557c0559b0682fec

@ -68,23 +68,23 @@
</message> </message>
<message> <message>
<source>Hidden Network</source> <source>Hidden Network</source>
<translation type="unfinished"></translation> <translation>Verborgenes Netzwerk</translation>
</message> </message>
<message> <message>
<source>CONNECT</source> <source>CONNECT</source>
<translation type="unfinished">CONNECT</translation> <translation>VERBINDEN</translation>
</message> </message>
<message> <message>
<source>Enter SSID</source> <source>Enter SSID</source>
<translation type="unfinished">SSID eingeben</translation> <translation>SSID eingeben</translation>
</message> </message>
<message> <message>
<source>Enter password</source> <source>Enter password</source>
<translation type="unfinished">Passwort eingeben</translation> <translation>Passwort eingeben</translation>
</message> </message>
<message> <message>
<source>for &quot;%1&quot;</source> <source>for &quot;%1&quot;</source>
<translation type="unfinished">für &quot;%1&quot;</translation> <translation>für "%1"</translation>
</message> </message>
</context> </context>
<context> <context>
@ -117,31 +117,31 @@
<name>DeveloperPanel</name> <name>DeveloperPanel</name>
<message> <message>
<source>Joystick Debug Mode</source> <source>Joystick Debug Mode</source>
<translation type="unfinished"></translation> <translation>Joystick Debug-Modus</translation>
</message> </message>
<message> <message>
<source>Longitudinal Maneuver Mode</source> <source>Longitudinal Maneuver Mode</source>
<translation type="unfinished"></translation> <translation>Längsmanöver-Modus</translation>
</message> </message>
<message> <message>
<source>openpilot Longitudinal Control (Alpha)</source> <source>openpilot Longitudinal Control (Alpha)</source>
<translation type="unfinished"></translation> <translation>openpilot Längsregelung (Alpha)</translation>
</message> </message>
<message> <message>
<source>WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).</source> <source>WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).</source>
<translation type="unfinished"></translation> <translation>WARNUNG: Die openpilot Längsregelung befindet sich für dieses Fahrzeug im Alpha-Stadium und deaktiviert das automatische Notbremsen (AEB).</translation>
</message> </message>
<message> <message>
<source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source> <source>On this car, openpilot defaults to the car&apos;s built-in ACC instead of openpilot&apos;s longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.</source>
<translation type="unfinished"></translation> <translation>Bei diesem Fahrzeug verwendet openpilot standardmäßig den eingebauten Tempomaten anstelle der openpilot Längsregelung. Aktiviere diese Option, um auf die openpilot Längsregelung umzuschalten. Es wird empfohlen, den experimentellen Modus zu aktivieren, wenn die openpilot Längsregelung (Alpha) aktiviert wird.</translation>
</message> </message>
<message> <message>
<source>Enable ADB</source> <source>Enable ADB</source>
<translation type="unfinished"></translation> <translation>ADB aktivieren</translation>
</message> </message>
<message> <message>
<source>ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. See https://docs.comma.ai/how-to/connect-to-comma for more info.</source> <source>ADB (Android Debug Bridge) allows connecting to your device over USB or over the network. See https://docs.comma.ai/how-to/connect-to-comma for more info.</source>
<translation type="unfinished"></translation> <translation>ADB (Android Debug Bridge) ermöglicht die Verbindung zu deinem Gerät über USB oder Netzwerk. Siehe https://docs.comma.ai/how-to/connect-to-comma für weitere Informationen.</translation>
</message> </message>
</context> </context>
<context> <context>
@ -280,11 +280,11 @@
</message> </message>
<message> <message>
<source>Pair Device</source> <source>Pair Device</source>
<translation type="unfinished"></translation> <translation>Gerät koppeln</translation>
</message> </message>
<message> <message>
<source>PAIR</source> <source>PAIR</source>
<translation type="unfinished"></translation> <translation>KOPPELN</translation>
</message> </message>
</context> </context>
<context> <context>
@ -309,36 +309,38 @@
<name>FirehosePanel</name> <name>FirehosePanel</name>
<message> <message>
<source>🔥 Firehose Mode 🔥</source> <source>🔥 Firehose Mode 🔥</source>
<translation type="unfinished"></translation> <translation>🔥 Firehose-Modus 🔥</translation>
</message> </message>
<message> <message>
<source>openpilot learns to drive by watching humans, like you, drive. <source>openpilot learns to drive by watching humans, like you, drive.
Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source> Firehose Mode allows you to maximize your training data uploads to improve openpilot&apos;s driving models. More data means bigger models, which means better Experimental Mode.</source>
<translation type="unfinished"></translation> <translation>openpilot lernt das Fahren, indem es Menschen wie dir beim Fahren zuschaut.
Der Firehose-Modus ermöglicht es dir, deine Trainingsdaten-Uploads zu maximieren, um die Fahrmodelle von openpilot zu verbessern. Mehr Daten bedeuten größere Modelle, was zu einem besseren Experimentellen Modus führt.</translation>
</message> </message>
<message> <message>
<source>Firehose Mode: ACTIVE</source> <source>Firehose Mode: ACTIVE</source>
<translation type="unfinished"></translation> <translation>Firehose-Modus: AKTIV</translation>
</message> </message>
<message> <message>
<source>ACTIVE</source> <source>ACTIVE</source>
<translation type="unfinished"></translation> <translation>AKTIV</translation>
</message> </message>
<message> <message>
<source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;Do all of my segments get pulled in Firehose Mode?&lt;/i&gt; No, we selectively pull a subset of your segments.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source> <source>For maximum effectiveness, bring your device inside and connect to a good USB-C adapter and Wi-Fi weekly.&lt;br&gt;&lt;br&gt;Firehose Mode can also work while you&apos;re driving if connected to a hotspot or unlimited SIM card.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Frequently Asked Questions&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter how or where I drive?&lt;/i&gt; Nope, just drive as you normally would.&lt;br&gt;&lt;br&gt;&lt;i&gt;Do all of my segments get pulled in Firehose Mode?&lt;/i&gt; No, we selectively pull a subset of your segments.&lt;br&gt;&lt;br&gt;&lt;i&gt;What&apos;s a good USB-C adapter?&lt;/i&gt; Any fast phone or laptop charger should be fine.&lt;br&gt;&lt;br&gt;&lt;i&gt;Does it matter which software I run?&lt;/i&gt; Yes, only upstream openpilot (and particular forks) are able to be used for training.</source>
<translation type="unfinished"></translation> <translation>Für maximale Effektivität bring dein Gerät jede Woche nach drinnen und verbinde es mit einem guten USB-C-Adapter und WLAN.&lt;br&gt;&lt;br&gt;Der Firehose-Modus funktioniert auch während der Fahrt, wenn das Gerät mit einem Hotspot oder einer ungedrosselten SIM-Karte verbunden ist.&lt;br&gt;&lt;br&gt;&lt;br&gt;&lt;b&gt;Häufig gestellte Fragen&lt;/b&gt;&lt;br&gt;&lt;br&gt;&lt;i&gt;Spielt es eine Rolle, wie oder wo ich fahre?&lt;/i&gt; Nein, fahre einfach wie gewohnt.&lt;br&gt;&lt;br&gt;&lt;i&gt;Werden im Firehose-Modus alle meine Segmente hochgeladen?&lt;/i&gt; Nein, wir wählen selektiv nur einen Teil deiner Segmente aus.&lt;br&gt;&lt;br&gt;&lt;i&gt;Welcher USB-C-Adapter ist gut?&lt;/i&gt; Jedes Schnellladegerät für Handy oder Laptop sollte ausreichen.&lt;br&gt;&lt;br&gt;&lt;i&gt;Spielt es eine Rolle, welche Software ich nutze?&lt;/i&gt; Ja, nur das offizielle Upstreamopenpilot (und bestimmte Forks) kann für das Training verwendet werden.</translation>
</message> </message>
<message numerus="yes"> <message numerus="yes">
<source>&lt;b&gt;%n segment(s)&lt;/b&gt; of your driving is in the training dataset so far.</source> <source>&lt;b&gt;%n segment(s)&lt;/b&gt; of your driving is in the training dataset so far.</source>
<translation type="unfinished"> <translation>
<numerusform></numerusform> <numerusform>&lt;b&gt;%n Segment&lt;/b&gt; deiner Fahrten ist bisher im Trainingsdatensatz.</numerusform>
<numerusform></numerusform> <numerusform>&lt;b&gt;%n Segmente&lt;/b&gt; deiner Fahrten sind bisher im Trainingsdatensatz.</numerusform>
</translation> </translation>
</message> </message>
<message> <message>
<source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to an unmetered network</source> <source>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INACTIVE&lt;/span&gt;: connect to an unmetered network</source>
<translation type="unfinished"></translation> <translation>&lt;span stylesheet=&apos;font-size: 60px; font-weight: bold; color: #e74c3c;&apos;&gt;INAKTIV&lt;/span&gt;: Verbinde dich mit einem ungedrosselten Netzwerk</translation>
</message> </message>
</context> </context>
<context> <context>
@ -411,48 +413,49 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
<name>OffroadAlert</name> <name>OffroadAlert</name>
<message> <message>
<source>Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won&apos;t engage in %1</source> <source>Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won&apos;t engage in %1</source>
<translation type="unfinished"></translation> <translation>Stelle sofort eine Internetverbindung her, um nach Updates zu suchen. Wenn du keine Verbindung herstellst, kann openpilot in %1 nicht mehr aktiviert werden.</translation>
</message> </message>
<message> <message>
<source>Connect to internet to check for updates. openpilot won&apos;t automatically start until it connects to internet to check for updates.</source> <source>Connect to internet to check for updates. openpilot won&apos;t automatically start until it connects to internet to check for updates.</source>
<translation type="unfinished"></translation> <translation>Verbinde dich mit dem Internet, um nach Updates zu suchen. openpilot startet nicht automatisch, bis eine Internetverbindung besteht und nach Updates gesucht wurde.</translation>
</message> </message>
<message> <message>
<source>Unable to download updates <source>Unable to download updates
%1</source> %1</source>
<translation type="unfinished"></translation> <translation>Updates konnten nicht heruntergeladen werden
%1</translation>
</message> </message>
<message> <message>
<source>Taking camera snapshots. System won&apos;t start until finished.</source> <source>Taking camera snapshots. System won&apos;t start until finished.</source>
<translation type="unfinished"></translation> <translation>Kamera-Snapshots werden aufgenommen. Das System startet erst, wenn dies abgeschlossen ist.</translation>
</message> </message>
<message> <message>
<source>An update to your device&apos;s operating system is downloading in the background. You will be prompted to update when it&apos;s ready to install.</source> <source>An update to your device&apos;s operating system is downloading in the background. You will be prompted to update when it&apos;s ready to install.</source>
<translation type="unfinished"></translation> <translation>Ein Update für das Betriebssystem deines Geräts wird im Hintergrund heruntergeladen. Du wirst aufgefordert, das Update zu installieren, sobald es bereit ist.</translation>
</message> </message>
<message> <message>
<source>Device failed to register. It will not connect to or upload to comma.ai servers, and receives no support from comma.ai. If this is an official device, visit https://comma.ai/support.</source> <source>Device failed to register. It will not connect to or upload to comma.ai servers, and receives no support from comma.ai. If this is an official device, visit https://comma.ai/support.</source>
<translation type="unfinished"></translation> <translation>Gerät konnte nicht registriert werden. Es wird keine Verbindung zu den comma.ai-Servern herstellen oder Daten hochladen und erhält keinen Support von comma.ai. Wenn dies ein offizielles Gerät ist, besuche https://comma.ai/support.</translation>
</message> </message>
<message> <message>
<source>NVMe drive not mounted.</source> <source>NVMe drive not mounted.</source>
<translation type="unfinished"></translation> <translation>NVMe-Laufwerk nicht gemounted.</translation>
</message> </message>
<message> <message>
<source>Unsupported NVMe drive detected. Device may draw significantly more power and overheat due to the unsupported NVMe.</source> <source>Unsupported NVMe drive detected. Device may draw significantly more power and overheat due to the unsupported NVMe.</source>
<translation type="unfinished"></translation> <translation>Nicht unterstütztes NVMe-Laufwerk erkannt. Das Gerät kann dadurch deutlich mehr Strom verbrauchen und überhitzen.</translation>
</message> </message>
<message> <message>
<source>openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.</source> <source>openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.</source>
<translation type="unfinished"></translation> <translation>openpilot konnte dein Auto nicht identifizieren. Dein Auto wird entweder nicht unterstützt oder die Steuergeräte (ECUs) werden nicht erkannt. Bitte reiche einen Pull Request ein, um die Firmware-Versionen für das richtige Fahrzeug hinzuzufügen. Hilfe findest du auf discord.comma.ai.</translation>
</message> </message>
<message> <message>
<source>openpilot detected a change in the device&apos;s mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield.</source> <source>openpilot detected a change in the device&apos;s mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield.</source>
<translation type="unfinished"></translation> <translation>openpilot hat eine Änderung der Montageposition des Geräts erkannt. Stelle sicher, dass das Gerät vollständig in der Halterung sitzt und die Halterung fest an der Windschutzscheibe befestigt ist.</translation>
</message> </message>
<message> <message>
<source>Device temperature too high. System cooling down before starting. Current internal component temperature: %1</source> <source>Device temperature too high. System cooling down before starting. Current internal component temperature: %1</source>
<translation type="unfinished"></translation> <translation>Gerätetemperatur zu hoch. Das System kühlt ab, bevor es startet. Aktuelle interne Komponententemperatur: %1</translation>
</message> </message>
</context> </context>
<context> <context>
@ -474,23 +477,23 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
<name>OnroadAlerts</name> <name>OnroadAlerts</name>
<message> <message>
<source>openpilot Unavailable</source> <source>openpilot Unavailable</source>
<translation type="unfinished"></translation> <translation>openpilot nicht verfügbar</translation>
</message> </message>
<message> <message>
<source>TAKE CONTROL IMMEDIATELY</source> <source>TAKE CONTROL IMMEDIATELY</source>
<translation type="unfinished"></translation> <translation>ÜBERNIMM SOFORT DIE KONTROLLE</translation>
</message> </message>
<message> <message>
<source>Reboot Device</source> <source>Reboot Device</source>
<translation type="unfinished"></translation> <translation>Gerät neu starten</translation>
</message> </message>
<message> <message>
<source>Waiting to start</source> <source>Waiting to start</source>
<translation type="unfinished"></translation> <translation>Warten auf Start</translation>
</message> </message>
<message> <message>
<source>System Unresponsive</source> <source>System Unresponsive</source>
<translation type="unfinished"></translation> <translation>System reagiert nicht</translation>
</message> </message>
</context> </context>
<context> <context>
@ -513,7 +516,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
</message> </message>
<message> <message>
<source>Please connect to Wi-Fi to complete initial pairing</source> <source>Please connect to Wi-Fi to complete initial pairing</source>
<translation type="unfinished"></translation> <translation>Bitte verbinde dich mit WLAN, um die Koppelung abzuschließen.</translation>
</message> </message>
</context> </context>
<context> <context>
@ -547,15 +550,15 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
</message> </message>
<message> <message>
<source>24/7 LTE connectivity</source> <source>24/7 LTE connectivity</source>
<translation type="unfinished"></translation> <translation>24/7 LTE-Verbindung</translation>
</message> </message>
<message> <message>
<source>1 year of drive storage</source> <source>1 year of drive storage</source>
<translation type="unfinished"></translation> <translation>Fahrdaten-Speicherung für 1 Jahr</translation>
</message> </message>
<message> <message>
<source>Remote snapshots</source> <source>Remote snapshots</source>
<translation type="unfinished"></translation> <translation>Remote-Snapshots</translation>
</message> </message>
</context> </context>
<context> <context>
@ -606,7 +609,7 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
</message> </message>
<message> <message>
<source>now</source> <source>now</source>
<translation type="unfinished"></translation> <translation>jetzt</translation>
</message> </message>
</context> </context>
<context> <context>
@ -637,16 +640,17 @@ Firehose Mode allows you to maximize your training data uploads to improve openp
</message> </message>
<message> <message>
<source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source> <source>Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.</source>
<translation type="unfinished"></translation> <translation>Datenpartition konnte nicht gemounted werden. Die Partition ist möglicherweise beschädigt. Drücke Bestätigen, um das Gerät zu löschen und zurückzusetzen.</translation>
</message> </message>
<message> <message>
<source>Resetting device... <source>Resetting device...
This may take up to a minute.</source> This may take up to a minute.</source>
<translation type="unfinished"></translation> <translation>Gerät wird zurückgesetzt...
Dies kann bis zu einer Minute dauern.</translation>
</message> </message>
<message> <message>
<source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source> <source>System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.</source>
<translation type="unfinished"></translation> <translation>System-Reset ausgelöst. Drücke Bestätigen, um alle Inhalte und Einstellungen zu löschen. Drücke Abbrechen, um den Startvorgang fortzusetzen.</translation>
</message> </message>
</context> </context>
<context> <context>
@ -673,11 +677,11 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>Developer</source> <source>Developer</source>
<translation type="unfinished"></translation> <translation>Entwickler</translation>
</message> </message>
<message> <message>
<source>Firehose</source> <source>Firehose</source>
<translation type="unfinished"></translation> <translation>Firehose</translation>
</message> </message>
</context> </context>
<context> <context>
@ -752,11 +756,11 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>No custom software found at this URL.</source> <source>No custom software found at this URL.</source>
<translation type="unfinished"></translation> <translation>Keine benutzerdefinierte Software unter dieser URL gefunden.</translation>
</message> </message>
<message> <message>
<source>Something went wrong. Reboot the device.</source> <source>Something went wrong. Reboot the device.</source>
<translation type="unfinished"></translation> <translation>Etwas ist schiefgelaufen. Starte das Gerät neu.</translation>
</message> </message>
<message> <message>
<source>Select a language</source> <source>Select a language</source>
@ -764,15 +768,15 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>Choose Software to Install</source> <source>Choose Software to Install</source>
<translation type="unfinished"></translation> <translation>Wähle die zu installierende Software</translation>
</message> </message>
<message> <message>
<source>openpilot</source> <source>openpilot</source>
<translation type="unfinished">openpilot</translation> <translation>openpilot</translation>
</message> </message>
<message> <message>
<source>Custom Software</source> <source>Custom Software</source>
<translation type="unfinished"></translation> <translation>Benutzerdefinierte Software</translation>
</message> </message>
</context> </context>
<context> <context>
@ -923,23 +927,23 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>failed to check for update</source> <source>failed to check for update</source>
<translation type="unfinished"></translation> <translation>Update-Prüfung fehlgeschlagen</translation>
</message> </message>
<message> <message>
<source>up to date, last checked %1</source> <source>up to date, last checked %1</source>
<translation type="unfinished"></translation> <translation>Auf dem neuesten Stand, zuletzt geprüft am %1</translation>
</message> </message>
<message> <message>
<source>DOWNLOAD</source> <source>DOWNLOAD</source>
<translation type="unfinished"></translation> <translation>HERUNTERLADEN</translation>
</message> </message>
<message> <message>
<source>update available</source> <source>update available</source>
<translation type="unfinished"></translation> <translation>Update verfügbar</translation>
</message> </message>
<message> <message>
<source>never</source> <source>never</source>
<translation type="unfinished"></translation> <translation>nie</translation>
</message> </message>
</context> </context>
<context> <context>
@ -1000,11 +1004,11 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>Welcome to openpilot</source> <source>Welcome to openpilot</source>
<translation type="unfinished"></translation> <translation>Willkommen bei openpilot</translation>
</message> </message>
<message> <message>
<source>You must accept the Terms and Conditions to use openpilot. Read the latest terms at &lt;span style=&apos;color: #465BEA;&apos;&gt;https://comma.ai/terms&lt;/span&gt; before continuing.</source> <source>You must accept the Terms and Conditions to use openpilot. Read the latest terms at &lt;span style=&apos;color: #465BEA;&apos;&gt;https://comma.ai/terms&lt;/span&gt; before continuing.</source>
<translation type="unfinished"></translation> <translation>Du musst die Nutzungsbedingungen akzeptieren, um openpilot zu verwenden. Lies die aktuellen Bedingungen unter &lt;span style=&apos;color: #465BEA;&apos;&gt;https://comma.ai/terms&lt;/span&gt;, bevor du fortfährst.</translation>
</message> </message>
</context> </context>
<context> <context>
@ -1071,51 +1075,51 @@ This may take up to a minute.</source>
</message> </message>
<message> <message>
<source>Aggressive</source> <source>Aggressive</source>
<translation type="unfinished"></translation> <translation>Aggressiv</translation>
</message> </message>
<message> <message>
<source>Standard</source> <source>Standard</source>
<translation type="unfinished"></translation> <translation>Standard</translation>
</message> </message>
<message> <message>
<source>Relaxed</source> <source>Relaxed</source>
<translation type="unfinished"></translation> <translation>Entspannt</translation>
</message> </message>
<message> <message>
<source>Driving Personality</source> <source>Driving Personality</source>
<translation type="unfinished"></translation> <translation>Fahrstil</translation>
</message> </message>
<message> <message>
<source>End-to-End Longitudinal Control</source> <source>End-to-End Longitudinal Control</source>
<translation type="unfinished"></translation> <translation>Ende-zu-Ende Längsregelung</translation>
</message> </message>
<message> <message>
<source>openpilot longitudinal control may come in a future update.</source> <source>openpilot longitudinal control may come in a future update.</source>
<translation type="unfinished"></translation> <translation>Die openpilot Längsregelung könnte in einem zukünftigen Update verfügbar sein.</translation>
</message> </message>
<message> <message>
<source>An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.</source> <source>An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches.</source>
<translation type="unfinished"></translation> <translation>Eine Alpha-Version der openpilot Längsregelung kann zusammen mit dem Experimentellen Modus auf non-stable Branches getestet werden.</translation>
</message> </message>
<message> <message>
<source>Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode.</source> <source>Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode.</source>
<translation type="unfinished"></translation> <translation>Aktiviere den Schalter für openpilot Längsregelung (Alpha), um den Experimentellen Modus zu erlauben.</translation>
</message> </message>
<message> <message>
<source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars. On supported cars, you can cycle through these personalities with your steering wheel distance button.</source> <source>Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars. On supported cars, you can cycle through these personalities with your steering wheel distance button.</source>
<translation type="unfinished"></translation> <translation>Standard wird empfohlen. Im aggressiven Modus folgt openpilot vorausfahrenden Fahrzeugen enger und ist beim Gasgeben und Bremsen aggressiver. Im entspannten Modus hält openpilot mehr Abstand zu vorausfahrenden Fahrzeugen. Bei unterstützten Fahrzeugen kannst du mit der Abstandstaste am Lenkrad zwischen diesen Fahrstilen wechseln.</translation>
</message> </message>
<message> <message>
<source>The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.</source> <source>The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner.</source>
<translation type="unfinished"></translation> <translation>Die Fahrvisualisierung wechselt bei niedrigen Geschwindigkeiten auf die nach vorne gerichtete Weitwinkelkamera, um Kurven besser darzustellen. Das Logo des Experimentellen Modus wird außerdem oben rechts angezeigt.</translation>
</message> </message>
<message> <message>
<source>Always-On Driver Monitoring</source> <source>Always-On Driver Monitoring</source>
<translation type="unfinished"></translation> <translation>Dauerhaft aktive Fahrerüberwachung</translation>
</message> </message>
<message> <message>
<source>Enable driver monitoring even when openpilot is not engaged.</source> <source>Enable driver monitoring even when openpilot is not engaged.</source>
<translation type="unfinished"></translation> <translation>Fahrerüberwachung auch aktivieren, wenn openpilot nicht aktiv ist.</translation>
</message> </message>
</context> </context>
<context> <context>
@ -1157,15 +1161,15 @@ This may take up to a minute.</source>
<name>WiFiPromptWidget</name> <name>WiFiPromptWidget</name>
<message> <message>
<source>Open</source> <source>Open</source>
<translation type="unfinished"></translation> <translation>Öffnen</translation>
</message> </message>
<message> <message>
<source>Maximize your training data uploads to improve openpilot&apos;s driving models.</source> <source>Maximize your training data uploads to improve openpilot&apos;s driving models.</source>
<translation type="unfinished"></translation> <translation>Maximiere deine Trainingsdaten-Uploads, um die Fahrmodelle von openpilot zu verbessern.</translation>
</message> </message>
<message> <message>
<source>&lt;span style=&apos;font-family: &quot;Noto Color Emoji&quot;;&apos;&gt;🔥&lt;/span&gt; Firehose Mode &lt;span style=&apos;font-family: Noto Color Emoji;&apos;&gt;🔥&lt;/span&gt;</source> <source>&lt;span style=&apos;font-family: &quot;Noto Color Emoji&quot;;&apos;&gt;🔥&lt;/span&gt; Firehose Mode &lt;span style=&apos;font-family: Noto Color Emoji;&apos;&gt;🔥&lt;/span&gt;</source>
<translation type="unfinished"></translation> <translation>&lt;span style=&apos;font-family: &quot;Noto Color Emoji&quot;;&apos;&gt;🔥&lt;/span&gt; Firehose-Modus &lt;span style=&apos;font-family: Noto Color Emoji;&apos;&gt;🔥&lt;/span&gt;</translation>
</message> </message>
</context> </context>
<context> <context>

@ -26,9 +26,6 @@ void CameraBuf::init(cl_device_id device_id, cl_context context, SpectraCamera *
LOGD("allocated %d CL buffers", frame_buf_count); LOGD("allocated %d CL buffers", frame_buf_count);
} }
out_img_width = sensor->frame_width;
out_img_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height;
// the encoder HW tells us the size it wants after setting it up. // the encoder HW tells us the size it wants after setting it up.
// TODO: VENUS_BUFFER_SIZE should give the size, but it's too small. dependent on encoder settings? // TODO: VENUS_BUFFER_SIZE should give the size, but it's too small. dependent on encoder settings?
size_t nv12_size = (out_img_width <= 1344 ? 2900 : 2346)*cam->stride; size_t nv12_size = (out_img_width <= 1344 ? 2900 : 2346)*cam->stride;

@ -32,7 +32,7 @@ public:
VisionBuf *cur_yuv_buf; VisionBuf *cur_yuv_buf;
VisionBuf *cur_camera_buf; VisionBuf *cur_camera_buf;
std::unique_ptr<VisionBuf[]> camera_bufs_raw; std::unique_ptr<VisionBuf[]> camera_bufs_raw;
int out_img_width, out_img_height; uint32_t out_img_width, out_img_height;
CameraBuf() = default; CameraBuf() = default;
~CameraBuf(); ~CameraBuf();

@ -73,7 +73,7 @@ void CameraState::init(VisionIpcServer *v, cl_device_id device_id, cl_context ct
if (!camera.enabled) return; if (!camera.enabled) return;
fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm; fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm / camera.sensor->out_scale;
set_exposure_rect(); set_exposure_rect();
dc_gain_weight = camera.sensor->dc_gain_min_weight; dc_gain_weight = camera.sensor->dc_gain_min_weight;
@ -107,10 +107,10 @@ void CameraState::set_exposure_rect() {
float fl_ref = ae_target.second; float fl_ref = ae_target.second;
ae_xywh = (Rect){ ae_xywh = (Rect){
std::max(0, camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), std::max(0, (int)camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)),
std::max(0, camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), std::max(0, (int)camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))),
std::min((int)(fl_pix / fl_ref * xywh_ref.w), camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), std::min((int)(fl_pix / fl_ref * xywh_ref.w), (int)camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)),
std::min((int)(fl_pix / fl_ref * xywh_ref.h), camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) std::min((int)(fl_pix / fl_ref * xywh_ref.h), (int)camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y)))
}; };
} }

@ -105,7 +105,7 @@ int build_update(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std:
} }
int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std::vector<uint32_t> &patches) { int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo *s, std::vector<uint32_t> &patches, uint32_t out_width, uint32_t out_height) {
uint8_t *start = dst; uint8_t *start = dst;
// start with the every frame config // start with the every frame config
@ -185,12 +185,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo
// output size/scaling // output size/scaling
dst += write_cont(dst, 0xa3c, { dst += write_cont(dst, 0xa3c, {
0x00000003, 0x00000003,
((s->frame_width - 1) << 16) | (s->frame_width - 1), ((out_width - 1) << 16) | (s->frame_width - 1),
0x30036666, 0x30036666,
0x00000000, 0x00000000,
0x00000000, 0x00000000,
s->frame_width - 1, s->frame_width - 1,
((s->frame_height - 1) << 16) | (s->frame_height - 1), ((out_height - 1) << 16) | (s->frame_height - 1),
0x30036666, 0x30036666,
0x00000000, 0x00000000,
0x00000000, 0x00000000,
@ -198,12 +198,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo
}); });
dst += write_cont(dst, 0xa68, { dst += write_cont(dst, 0xa68, {
0x00000003, 0x00000003,
((s->frame_width/2 - 1) << 16) | (s->frame_width - 1), ((out_width / 2 - 1) << 16) | (s->frame_width - 1),
0x3006cccc, 0x3006cccc,
0x00000000, 0x00000000,
0x00000000, 0x00000000,
s->frame_width - 1, s->frame_width - 1,
((s->frame_height/2 - 1) << 16) | (s->frame_height - 1), ((out_height / 2 - 1) << 16) | (s->frame_height - 1),
0x3006cccc, 0x3006cccc,
0x00000000, 0x00000000,
0x00000000, 0x00000000,
@ -212,12 +212,12 @@ int build_initial_config(uint8_t *dst, const CameraConfig cam, const SensorInfo
// cropping // cropping
dst += write_cont(dst, 0xe10, { dst += write_cont(dst, 0xe10, {
s->frame_height - 1, out_height - 1,
s->frame_width - 1, out_width - 1,
}); });
dst += write_cont(dst, 0xe30, { dst += write_cont(dst, 0xe30, {
s->frame_height/2 - 1, out_height / 2 - 1,
s->frame_width - 1, out_width - 1,
}); });
dst += write_cont(dst, 0xe18, { dst += write_cont(dst, 0xe18, {
0x0ff00000, 0x0ff00000,

@ -281,18 +281,21 @@ void SpectraCamera::camera_open(VisionIpcServer *v, cl_device_id device_id, cl_c
if (!enabled) return; if (!enabled) return;
buf.out_img_width = sensor->frame_width / sensor->out_scale;
buf.out_img_height = (sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height) / sensor->out_scale;
// size is driven by all the HW that handles frames, // size is driven by all the HW that handles frames,
// the video encoder has certain alignment requirements in this case // the video encoder has certain alignment requirements in this case
stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, sensor->frame_width); stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, buf.out_img_width);
y_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); y_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, buf.out_img_height);
uv_height = VENUS_UV_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); uv_height = VENUS_UV_SCANLINES(COLOR_FMT_NV12, buf.out_img_height);
uv_offset = stride*y_height; uv_offset = stride*y_height;
yuv_size = uv_offset + stride*uv_height; yuv_size = uv_offset + stride*uv_height;
if (cc.output_type != ISP_RAW_OUTPUT) { if (cc.output_type != ISP_RAW_OUTPUT) {
uv_offset = ALIGNED_SIZE(uv_offset, 0x1000); uv_offset = ALIGNED_SIZE(uv_offset, 0x1000);
yuv_size = uv_offset + ALIGNED_SIZE(stride*uv_height, 0x1000); yuv_size = uv_offset + ALIGNED_SIZE(stride*uv_height, 0x1000);
} }
assert(stride == VENUS_UV_STRIDE(COLOR_FMT_NV12, sensor->frame_width)); assert(stride == VENUS_UV_STRIDE(COLOR_FMT_NV12, buf.out_img_width));
assert(y_height/2 == uv_height); assert(y_height/2 == uv_height);
open = true; open = true;
@ -645,14 +648,14 @@ void SpectraCamera::config_bps(int idx, int request_id) {
io_cfg[1].mem_handle[0] = buf_handle_yuv[idx]; io_cfg[1].mem_handle[0] = buf_handle_yuv[idx];
io_cfg[1].mem_handle[1] = buf_handle_yuv[idx]; io_cfg[1].mem_handle[1] = buf_handle_yuv[idx];
io_cfg[1].planes[0] = (struct cam_plane_cfg){ io_cfg[1].planes[0] = (struct cam_plane_cfg){
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height, .height = buf.out_img_height,
.plane_stride = stride, .plane_stride = stride,
.slice_height = y_height, .slice_height = y_height,
}; };
io_cfg[1].planes[1] = (struct cam_plane_cfg){ io_cfg[1].planes[1] = (struct cam_plane_cfg){
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height/2, .height = buf.out_img_height / 2,
.plane_stride = stride, .plane_stride = stride,
.slice_height = uv_height, .slice_height = uv_height,
}; };
@ -737,7 +740,7 @@ void SpectraCamera::config_ife(int idx, int request_id, bool init) {
bool is_raw = cc.output_type != ISP_IFE_PROCESSED; bool is_raw = cc.output_type != ISP_IFE_PROCESSED;
if (!is_raw) { if (!is_raw) {
if (init) { if (init) {
buf_desc[0].length = build_initial_config((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches); buf_desc[0].length = build_initial_config((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches, buf.out_img_width, buf.out_img_height);
} else { } else {
buf_desc[0].length = build_update((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches); buf_desc[0].length = build_update((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, cc, sensor.get(), patches);
} }
@ -844,14 +847,14 @@ void SpectraCamera::config_ife(int idx, int request_id, bool init) {
io_cfg[0].mem_handle[0] = buf_handle_yuv[idx]; io_cfg[0].mem_handle[0] = buf_handle_yuv[idx];
io_cfg[0].mem_handle[1] = buf_handle_yuv[idx]; io_cfg[0].mem_handle[1] = buf_handle_yuv[idx];
io_cfg[0].planes[0] = (struct cam_plane_cfg){ io_cfg[0].planes[0] = (struct cam_plane_cfg){
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height, .height = buf.out_img_height,
.plane_stride = stride, .plane_stride = stride,
.slice_height = y_height, .slice_height = y_height,
}; };
io_cfg[0].planes[1] = (struct cam_plane_cfg){ io_cfg[0].planes[1] = (struct cam_plane_cfg){
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height/2, .height = buf.out_img_height / 2,
.plane_stride = stride, .plane_stride = stride,
.slice_height = uv_height, .slice_height = uv_height,
}; };
@ -993,6 +996,9 @@ bool SpectraCamera::openSensor() {
LOGD("-- Probing sensor %d", cc.camera_num); LOGD("-- Probing sensor %d", cc.camera_num);
auto init_sensor_lambda = [this](SensorInfo *s) { auto init_sensor_lambda = [this](SensorInfo *s) {
if (s->image_sensor == cereal::FrameData::ImageSensor::OS04C10 && cc.output_type == ISP_IFE_PROCESSED) {
((OS04C10*)s)->ife_downscale_configure();
}
sensor.reset(s); sensor.reset(s);
return (sensors_init() == 0); return (sensors_init() == 0);
}; };
@ -1065,8 +1071,8 @@ void SpectraCamera::configISP() {
.data[0] = (struct cam_isp_out_port_info){ .data[0] = (struct cam_isp_out_port_info){
.res_type = CAM_ISP_IFE_OUT_RES_FULL, .res_type = CAM_ISP_IFE_OUT_RES_FULL,
.format = CAM_FORMAT_NV12, .format = CAM_FORMAT_NV12,
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height + sensor->extra_height, .height = buf.out_img_height + sensor->extra_height,
.comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0,
}, },
}; };
@ -1141,8 +1147,8 @@ void SpectraCamera::configICP() {
}, },
.out_res[0] = (struct cam_icp_res_info){ .out_res[0] = (struct cam_icp_res_info){
.format = 0x3, // YUV420NV12 .format = 0x3, // YUV420NV12
.width = sensor->frame_width, .width = buf.out_img_width,
.height = sensor->frame_height, .height = buf.out_img_height,
.fps = 20, .fps = 20,
}, },
}; };

@ -20,6 +20,17 @@ const uint32_t os04c10_analog_gains_reg[] = {
} // namespace } // namespace
void OS04C10::ife_downscale_configure() {
out_scale = 2;
pixel_size_mm = 0.002;
frame_width = 2688;
frame_height = 1520;
exposure_time_max = 2352;
init_reg_array.insert(init_reg_array.end(), std::begin(ife_downscale_override_array_os04c10), std::end(ife_downscale_override_array_os04c10));
}
OS04C10::OS04C10() { OS04C10::OS04C10() {
image_sensor = cereal::FrameData::ImageSensor::OS04C10; image_sensor = cereal::FrameData::ImageSensor::OS04C10;
bayer_pattern = CAM_ISP_PATTERN_BAYER_BGBGBG; bayer_pattern = CAM_ISP_PATTERN_BAYER_BGBGBG;

@ -88,8 +88,6 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
{0x37c7, 0xa8}, {0x37c7, 0xa8},
{0x37da, 0x11}, {0x37da, 0x11},
{0x381f, 0x08}, {0x381f, 0x08},
// {0x3829, 0x03},
// {0x3832, 0x00},
{0x3881, 0x00}, {0x3881, 0x00},
{0x3888, 0x04}, {0x3888, 0x04},
{0x388b, 0x00}, {0x388b, 0x00},
@ -199,7 +197,6 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
{0x370b, 0x48}, {0x370b, 0x48},
{0x370c, 0x01}, {0x370c, 0x01},
{0x370f, 0x00}, {0x370f, 0x00},
{0x3714, 0x28},
{0x3716, 0x04}, {0x3716, 0x04},
{0x3719, 0x11}, {0x3719, 0x11},
{0x371a, 0x1e}, {0x371a, 0x1e},
@ -231,7 +228,6 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
{0x37bd, 0x01}, {0x37bd, 0x01},
{0x37bf, 0x26}, {0x37bf, 0x26},
{0x37c0, 0x11}, {0x37c0, 0x11},
{0x37c2, 0x14},
{0x37cd, 0x19}, {0x37cd, 0x19},
{0x37e0, 0x08}, {0x37e0, 0x08},
{0x37e6, 0x04}, {0x37e6, 0x04},
@ -241,14 +237,9 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
{0x37d8, 0x02}, {0x37d8, 0x02},
{0x37e2, 0x10}, {0x37e2, 0x10},
{0x3739, 0x10}, {0x3739, 0x10},
{0x3662, 0x08},
{0x37e4, 0x20}, {0x37e4, 0x20},
{0x37e3, 0x08}, {0x37e3, 0x08},
{0x37d9, 0x04},
{0x4040, 0x00}, {0x4040, 0x00},
{0x4041, 0x03},
{0x4008, 0x01},
{0x4009, 0x06},
// FSIN // FSIN
{0x3002, 0x22}, {0x3002, 0x22},
@ -269,20 +260,11 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
{0x3802, 0x00}, {0x3803, 0x00}, {0x3802, 0x00}, {0x3803, 0x00},
{0x3804, 0x0a}, {0x3805, 0x8f}, {0x3804, 0x0a}, {0x3805, 0x8f},
{0x3806, 0x05}, {0x3807, 0xff}, {0x3806, 0x05}, {0x3807, 0xff},
{0x3808, 0x05}, {0x3809, 0x40},
{0x380a, 0x02}, {0x380b, 0xf8},
{0x3811, 0x08}, {0x3811, 0x08},
{0x3813, 0x08}, {0x3813, 0x08},
{0x3814, 0x03},
{0x3815, 0x01}, {0x3815, 0x01},
{0x3816, 0x03},
{0x3817, 0x01}, {0x3817, 0x01},
{0x380c, 0x0b}, {0x380d, 0xac}, // HTS
{0x380e, 0x06}, {0x380f, 0x9c}, // VTS
{0x3820, 0xb3},
{0x3821, 0x01},
{0x3880, 0x00}, {0x3880, 0x00},
{0x3882, 0x20}, {0x3882, 0x20},
{0x3c91, 0x0b}, {0x3c91, 0x0b},
@ -331,4 +313,40 @@ const struct i2c_random_wr_payload init_array_os04c10[] = {
// r // r
{0x5104, 0x08}, {0x5105, 0xd6}, {0x5104, 0x08}, {0x5105, 0xd6},
{0x5144, 0x08}, {0x5145, 0xd6}, {0x5144, 0x08}, {0x5145, 0xd6},
{0x3714, 0x28},
{0x37c2, 0x14},
{0x3662, 0x08},
{0x37d9, 0x04},
{0x4041, 0x03},
{0x4008, 0x01},
{0x4009, 0x06},
{0x3808, 0x05}, {0x3809, 0x40},
{0x380a, 0x02}, {0x380b, 0xf8},
{0x3814, 0x03},
{0x3816, 0x03},
{0x380c, 0x0b}, {0x380d, 0xac}, // HTS
{0x380e, 0x06}, {0x380f, 0x9c}, // VTS
{0x3820, 0xb3},
{0x3821, 0x01},
};
const struct i2c_random_wr_payload ife_downscale_override_array_os04c10[] = {
// OS04C10_AA_00_02_17_wAO_2688x1524_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz
{0x3829, 0x03},
{0x3714, 0x24},
{0x37c2, 0x04},
{0x3662, 0x10},
{0x37d9, 0x08},
{0x4041, 0x07},
{0x4008, 0x02},
{0x4009, 0x0d},
{0x3808, 0x0a}, {0x3809, 0x80},
{0x380a, 0x05}, {0x380b, 0xf0},
{0x3814, 0x01},
{0x3816, 0x01},
{0x380c, 0x08}, {0x380d, 0x5c}, // HTS
{0x380e, 0x09}, {0x380f, 0x38}, // VTS
{0x3820, 0xb0},
{0x3821, 0x00},
}; };

@ -29,6 +29,7 @@ public:
uint32_t frame_stride; uint32_t frame_stride;
uint32_t frame_offset = 0; uint32_t frame_offset = 0;
uint32_t extra_height = 0; uint32_t extra_height = 0;
int out_scale = 1;
int registers_offset = -1; int registers_offset = -1;
int stats_offset = -1; int stats_offset = -1;
int hdr_offset = -1; int hdr_offset = -1;
@ -109,6 +110,7 @@ public:
class OS04C10 : public SensorInfo { class OS04C10 : public SensorInfo {
public: public:
OS04C10(); OS04C10();
void ife_downscale_configure();
std::vector<i2c_random_wr_payload> getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; std::vector<i2c_random_wr_payload> getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override;
float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override;
int getSlaveAddress(int port) const override; int getSlaveAddress(int port) const override;

Loading…
Cancel
Save