Skip to content

Commit

Permalink
October 2024 Update
Browse files Browse the repository at this point in the history
  • Loading branch information
FrogAi committed Oct 1, 2024
1 parent c3b96a1 commit 909f66a
Show file tree
Hide file tree
Showing 129 changed files with 902 additions and 6,855 deletions.
1 change: 0 additions & 1 deletion SConstruct
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,6 @@ if arch == "Darwin":
]
qt_dirs += [f"{qt_env['QTDIR']}/include/Qt{m}" for m in qt_modules]
qt_env["LINKFLAGS"] += ["-F" + os.path.join(qt_env['QTDIR'], "lib")]
qt_env["LINKFLAGS"] += ["-rdynamic"]
qt_env["FRAMEWORKS"] += [f"Qt{m}" for m in qt_modules] + ["OpenGL"]
qt_env.AppendENVPath('PATH', os.path.join(qt_env['QTDIR'], "bin"))
else:
Expand Down
30 changes: 0 additions & 30 deletions changes.diff

This file was deleted.

5 changes: 3 additions & 2 deletions common/params.cc
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,8 @@ std::unordered_map<std::string, uint32_t> keys = {
{"CertifiedHerbalistDrives", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CertifiedHerbalistLiveTorqueParameters", PERSISTENT},
{"CertifiedHerbalistScore", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESignal", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESignalSpeed", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESignalLaneDetection", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESlowerLead", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESpeed", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"CESpeedLead", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
Expand Down Expand Up @@ -359,6 +360,7 @@ std::unordered_map<std::string, uint32_t> keys = {
{"HumanAcceleration", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"HumanFollowing", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"IconToDownload", PERSISTENT},
{"IncreasedStoppedDistance", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"IncreaseThermalLimits", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"JerkInfo", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VISUALS},
{"LaneChangeCustomizations", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
Expand Down Expand Up @@ -543,7 +545,6 @@ std::unordered_map<std::string, uint32_t> keys = {
{"SteerRatio", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"SteerRatioStock", PERSISTENT},
{"StoppedTimer", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_VISUALS},
{"StoppingDistance", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"TacoTune", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_CONTROLS},
{"TetheringEnabled", PERSISTENT | FROGPILOT_STORAGE | FROGPILOT_OTHER},
{"ThemeDownloadProgress", PERSISTENT},
Expand Down
41 changes: 2 additions & 39 deletions panda/board/safety/safety_toyota.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,35 +27,6 @@ const SteeringLimits TOYOTA_STEERING_LIMITS = {
},
};

const SteeringLimits TOYOTA_STEERING_LIMITS_TACO = {
.max_steer = 1750,
.max_rate_up = 20, // ramp up slow
.max_rate_down = 30, // ramp down fast
.max_torque_error = 350, // max torque cmd in excess of motor torque
.max_rt_delta = 450, // the real time limit is 1800/sec, a 20% buffer
.max_rt_interval = 250000,
.type = TorqueMotorLimited,

// the EPS faults when the steering angle rate is above a certain threshold for too long. to prevent this,
// we allow setting STEER_REQUEST bit to 0 while maintaining the requested torque value for a single frame
.min_valid_request_frames = 18,
.max_invalid_request_frames = 1,
.min_valid_request_rt_interval = 170000, // 170ms; a ~10% buffer on cutting every 19 frames
.has_steer_req_tolerance = true,

// LTA angle limits
// factor for STEER_TORQUE_SENSOR->STEER_ANGLE and STEERING_LTA->STEER_ANGLE_CMD (1 / 0.0573)
.angle_deg_to_can = 17.452007,
.angle_rate_up_lookup = {
{5., 25., 25.},
{0.3, 0.15, 0.15}
},
.angle_rate_down_lookup = {
{5., 25., 25.},
{0.36, 0.26, 0.26}
},
};

const int TOYOTA_LTA_MAX_ANGLE = 1657; // EPS only accepts up to 94.9461
const int TOYOTA_LTA_MAX_MEAS_TORQUE = 1500;
const int TOYOTA_LTA_MAX_DRIVER_TORQUE = 150;
Expand Down Expand Up @@ -142,7 +113,6 @@ bool toyota_alt_brake = false;
bool toyota_stock_longitudinal = false;
bool toyota_lta = false;
int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
float v_ego = 0.;

static uint32_t toyota_compute_checksum(const CANPacket_t *to_push) {
int addr = GET_ADDR(to_push);
Expand Down Expand Up @@ -242,7 +212,6 @@ static void toyota_rx_hook(const CANPacket_t *to_push) {
// check that all wheel speeds are at zero value
vehicle_moving = speed != 0;

v_ego = speed / 4.0 * 0.01 / 3.6;
UPDATE_VEHICLE_SPEED(speed / 4.0 * 0.01 / 3.6);
}

Expand Down Expand Up @@ -340,14 +309,8 @@ static bool toyota_tx_hook(const CANPacket_t *to_send) {
}
} else {
// check angle rate limits and inactive angle
if (v_ego < 11.0) {
if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS_TACO)) {
tx = false;
}
} else {
if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS)) {
tx = false;
}
if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS)) {
tx = false;
}

if (lta_request != lta_request2) {
Expand Down
1 change: 0 additions & 1 deletion selfdrive/car/toyota/carcontroller.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,6 @@ def update(self, CC, CS, now_nanos, frogpilot_toggles):
can_sends = []

# *** steer torque ***
self.params = CarControllerParams(self.CP, CS.out.vEgoRaw)
new_steer = int(round(actuators.steer * self.params.STEER_MAX))
apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params)

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/car/toyota/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ def _get_params(ret, candidate, fingerprint, car_fw, disable_openpilot_long, exp
tune.kiBP = [0., 5., 35.]
tune.kiV = [3.6, 2.4, 1.5]

if params.get_bool("FrogsGoMoosTweak"):
if ret.flags & ToyotaFlags.RAISED_ACCEL_LIMIT and params.get_bool("FrogsGoMoosTweak"):
ret.vEgoStopping = 0.15
ret.vEgoStarting = 0.15
ret.stoppingDecelRate = 0.1 # reach stopping target smoothly
Expand Down
10 changes: 2 additions & 8 deletions selfdrive/car/toyota/values.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,8 @@ def __init__(self, CP):
self.ACCEL_MIN = -3.5 # m/s2

if CP.lateralTuning.which == 'torque':
if vEgoRaw < 11.0:
self.STEER_DELTA_UP = 20
self.STEER_DELTA_DOWN = 30
self.STEER_MAX = 1750
else:
self.STEER_DELTA_UP = 15 # 1.0s time to peak torque
self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
self.STEER_MAX = 1500
self.STEER_DELTA_UP = 15 # 1.0s time to peak torque
self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
else:
self.STEER_DELTA_UP = 10 # 1.5s time to peak torque
self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50)
Expand Down
23 changes: 12 additions & 11 deletions selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,13 +105,13 @@ def get_T_FOLLOW(aggressive_follow=1.25, standard_follow=1.45, relaxed_follow=1.
def get_stopped_equivalence_factor(v_lead):
return (v_lead**2) / (2 * COMFORT_BRAKE)

def get_safe_obstacle_distance(v_ego, t_follow, stopping_distance):
return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + max(stopping_distance, STOP_DISTANCE - 1)
def get_safe_obstacle_distance(v_ego, t_follow):
return (v_ego**2) / (2 * COMFORT_BRAKE) + t_follow * v_ego + STOP_DISTANCE

def desired_follow_distance(v_ego, v_lead, t_follow=None):
if t_follow is None:
t_follow = get_T_FOLLOW()
return get_safe_obstacle_distance(v_ego, t_follow, STOP_DISTANCE) - get_stopped_equivalence_factor(v_lead)
return get_safe_obstacle_distance(v_ego, t_follow) - get_stopped_equivalence_factor(v_lead)


def gen_long_model():
Expand Down Expand Up @@ -181,7 +181,7 @@ def gen_long_ocp():
ocp.cost.yref = np.zeros((COST_DIM, ))
ocp.cost.yref_e = np.zeros((COST_E_DIM, ))

desired_dist_comfort = get_safe_obstacle_distance(v_ego, lead_t_follow, STOP_DISTANCE)
desired_dist_comfort = get_safe_obstacle_distance(v_ego, lead_t_follow)

# The main cost in normal operation is how close you are to the "desired" distance
# from an obstacle at every timestep. This obstacle can be a lead car
Expand Down Expand Up @@ -326,10 +326,10 @@ def extrapolate_lead(x_lead, v_lead, a_lead, a_lead_tau):
lead_xv = np.column_stack((x_lead_traj, v_lead_traj))
return lead_xv

def process_lead(self, lead, increased_stopping_distance=0):
def process_lead(self, lead, increased_distance=0):
v_ego = self.x0[1]
if lead is not None and lead.status:
x_lead = lead.dRel - increased_stopping_distance
x_lead = lead.dRel - increased_distance
v_lead = lead.vLead
a_lead = lead.aLeadK
a_lead_tau = lead.aLeadTau
Expand All @@ -355,11 +355,12 @@ def set_accel_limits(self, min_a, max_a):
self.cruise_min_a = min_a
self.max_a = max_a

def update(self, lead_one, lead_two, v_cruise, x, v, a, j, radarless_model, t_follow, frogpilot_toggles, personality=log.LongitudinalPersonality.standard):
def update(self, lead_one, lead_two, v_cruise, x, v, a, j, radarless_model, t_follow, trafficModeActive, frogpilot_toggles, personality=log.LongitudinalPersonality.standard):
v_ego = self.x0[1]
self.status = lead_one.status or lead_two.status
increased_distance = max(frogpilot_toggles.increase_stopped_distance + min(10 - v_ego, 0), 0) if not trafficModeActive else 0

lead_xv_0 = self.process_lead(lead_one)
lead_xv_0 = self.process_lead(lead_one, increased_distance)
lead_xv_1 = self.process_lead(lead_two)

# To estimate a safe distance from a moving lead, we calculate how much stopping
Expand All @@ -382,7 +383,7 @@ def update(self, lead_one, lead_two, v_cruise, x, v, a, j, radarless_model, t_fo
v_cruise_clipped = np.clip(v_cruise * np.ones(N+1),
v_lower,
v_upper)
cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, t_follow, frogpilot_toggles.stopping_distance)
cruise_obstacle = np.cumsum(T_DIFFS * v_cruise_clipped) + get_safe_obstacle_distance(v_cruise_clipped, t_follow)
x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle])
self.source = SOURCES[np.argmin(x_obstacles[0])]

Expand Down Expand Up @@ -428,9 +429,9 @@ def update(self, lead_one, lead_two, v_cruise, x, v, a, j, radarless_model, t_fo
# Check if it got within lead comfort range
# TODO This should be done cleaner
if self.mode == 'blended':
if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow, frogpilot_toggles.stopping_distance))- self.x_sol[:,0] < 0.0):
if any((lead_0_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0):
self.source = 'lead0'
if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow, frogpilot_toggles.stopping_distance))- self.x_sol[:,0] < 0.0) and \
if any((lead_1_obstacle - get_safe_obstacle_distance(self.x_sol[:,1], t_follow))- self.x_sol[:,0] < 0.0) and \
(lead_1_obstacle[0] - lead_0_obstacle[0]):
self.source = 'lead1'

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/controls/lib/longitudinal_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ def update(self, radarless_model, sm, frogpilot_toggles):
self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired)
x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error, v_ego, frogpilot_toggles.taco_tune)
self.mpc.update(self.lead_one, self.lead_two, sm['frogpilotPlan'].vCruise, x, v, a, j, radarless_model, sm['frogpilotPlan'].tFollow,
frogpilot_toggles, personality=sm['controlsState'].personality)
sm['frogpilotCarState'].trafficModeActive, frogpilot_toggles, personality=sm['controlsState'].personality)

self.a_desired_trajectory_full = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.a_solution)
self.v_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.v_solution)
Expand Down
4 changes: 2 additions & 2 deletions selfdrive/frogpilot/assets/model_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@

VERSION = "v8"

DEFAULT_MODEL = "game-boy"
DEFAULT_MODEL_NAME = "Game Boy (Default)"
DEFAULT_MODEL = "north-dakota-v2"
DEFAULT_MODEL_NAME = "North Dakota V2 (Default)"

def process_model_name(model_name):
cleaned_name = re.sub(r'[🗺️👀📡]', '', model_name)
Expand Down
Binary file not shown.
Binary file not shown.
5 changes: 3 additions & 2 deletions selfdrive/frogpilot/controls/frogpilot_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,9 @@ def update(self, carState, controlsState, frogpilotCarControl, frogpilotCarState

driving_gear = carState.gearShifter not in NON_DRIVING_GEARS

lead_distance = self.lead_one.dRel
stopping_distance = frogpilot_toggles.stopping_distance if not frogpilotCarState.trafficModeActive else STOP_DISTANCE
distance_offset = max(frogpilot_toggles.increase_stopped_distance + min(10 - v_ego, 0), 0) if not frogpilotCarState.trafficModeActive else 0
lead_distance = self.lead_one.dRel - distance_offset
stopping_distance = STOP_DISTANCE + distance_offset

self.frogpilot_acceleration.update(controlsState, frogpilotCarState, v_cruise, v_ego, frogpilot_toggles)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ def check_conditions(self, carState, frogpilotNavigation, modelData, following_l
return True

desired_lane = self.frogpilot_planner.lane_width_left if carState.leftBlinker else self.frogpilot_planner.lane_width_right
lane_available = desired_lane >= frogpilot_toggles.lane_detection_width
if frogpilot_toggles.conditional_signal and v_ego < CITY_SPEED_LIMIT and (carState.leftBlinker or carState.rightBlinker) and not lane_available:
lane_available = desired_lane >= frogpilot_toggles.lane_detection_width or not frogpilot_toggles.conditional_signal_lane_detection or not frogpilot_toggles.lane_detection
if v_ego < frogpilot_toggles.conditional_signal and (carState.leftBlinker or carState.rightBlinker) and not lane_available:
self.status_value = 9
return True

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/frogpilot/controls/lib/frogpilot_following.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ def update(self, aEgo, controlsState, frogpilotCarState, lead_distance, stopping
self.following_lead = self.frogpilot_planner.tracking_lead and lead_distance < (self.t_follow + 1) * v_ego

if self.frogpilot_planner.tracking_lead:
self.safe_obstacle_distance = int(get_safe_obstacle_distance(v_ego, self.t_follow, stopping_distance))
self.safe_obstacle_distance = int(get_safe_obstacle_distance(v_ego, self.t_follow))
self.safe_obstacle_distance_stock = self.safe_obstacle_distance
self.stopped_equivalence_factor = int(get_stopped_equivalence_factor(v_lead))
self.update_follow_values(lead_distance, stopping_distance, v_ego, v_lead, frogpilot_toggles)
Expand Down
46 changes: 15 additions & 31 deletions selfdrive/frogpilot/frogpilot_functions.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,16 +111,22 @@ def cleanup_backup(in_progress_destination, in_progress_compressed_backup):
print(f"An unexpected error occurred while trying to delete the incomplete {backup} backup: {e}")

def backup_frogpilot(build_metadata, params):
maximum_backups = 5
minimum_backup_size = params.get_int("MinimumBackupSize")

backup_path = "/data/backups"
cleanup_backups(backup_path, 4, minimum_backup_size, True)
cleanup_backups(backup_path, maximum_backups - 1, minimum_backup_size, True)

branch = build_metadata.channel
commit = build_metadata.openpilot.git_commit_date[12:-16]
total, used, free = shutil.disk_usage(backup_path)
required_free_space = minimum_backup_size * maximum_backups

backup_dir = os.path.join(backup_path, f"{branch}_{commit}_auto")
backup_directory(BASEDIR, backup_dir, f"Successfully backed up FrogPilot to {backup_dir}.", f"Failed to backup FrogPilot to {backup_dir}.", minimum_backup_size, params, True)
if free > required_free_space:
branch = build_metadata.channel
commit = build_metadata.openpilot.git_commit_date[12:-16]

backup_dir = os.path.join(backup_path, f"{branch}_{commit}_auto")

backup_directory(BASEDIR, backup_dir, f"Successfully backed up FrogPilot to {backup_dir}.", f"Failed to backup FrogPilot to {backup_dir}.", minimum_backup_size, params, True)

def backup_toggles(params, params_storage):
for key in params.all_keys():
Expand All @@ -129,8 +135,10 @@ def backup_toggles(params, params_storage):
if value is not None:
params_storage.put(key, value)

maximum_backups = 10

backup_path = "/data/toggle_backups"
cleanup_backups(backup_path, 9)
cleanup_backups(backup_path, 10 - 1)

backup_dir = os.path.join(backup_path, datetime.datetime.now().strftime('%Y-%m-%d_%I-%M%p').lower() + "_auto")
backup_directory("/data/params/d", backup_dir, f"Successfully backed up toggles to {backup_dir}.", f"Failed to backup toggles to {backup_dir}.")
Expand Down Expand Up @@ -196,33 +204,9 @@ def decrease_param(key):
except Exception as e:
print(f"An error occurred when converting params: {e}")

for key in ["PathWidth"]:
for key in ["LaneDetectionWidth", "PathWidth"]:
decrease_param(key)

def increase_param(key):
try:
metric = params_storage.get_bool("IsMetric")
value = params_storage.get_float(key)

if metric:
if value <= 5:
value += 6
params.put_float(key, value)
params_storage.put_float(key, value)
else:
if value <= 10:
value += 20
params.put_float(key, value)
params_storage.put_float(key, value)

except (UnknownKeyName, ValueError):
pass
except Exception as e:
print(f"An error occurred when converting params: {e}")

for key in ["StoppingDistance"]:
increase_param(key)

print("Param conversion completed")

def delete_file(file):
Expand Down
Loading

0 comments on commit 909f66a

Please sign in to comment.