Map Turn Speed Control

Added toggle for "Map Turn Speed Control".

Credit goes to Pfeiferj!

https: //github.com/pfeiferj
Co-Authored-By: Jacob Pfeifer <jacob@pfeifer.dev>
This commit is contained in:
FrogAi
2024-01-12 22:39:30 -07:00
parent 1a2f936da5
commit 46b0b80f47
11 changed files with 194 additions and 5 deletions

View File

@@ -28,6 +28,7 @@ struct FrogPilotLateralPlan @0xda96579883444c35 {
} }
struct FrogPilotLongitudinalPlan @0x80ae746ee2596b11 { struct FrogPilotLongitudinalPlan @0x80ae746ee2596b11 {
adjustedCruise @0: Float32;
conditionalExperimental @1 :Bool; conditionalExperimental @1 :Bool;
desiredFollowDistance @2 :Int16; desiredFollowDistance @2 :Int16;
distances @3 :List(Float32); distances @3 :List(Float32);

View File

@@ -262,7 +262,10 @@ std::unordered_map<std::string, uint32_t> keys = {
{"LongitudinalTune", PERSISTENT}, {"LongitudinalTune", PERSISTENT},
{"LongPitch", PERSISTENT}, {"LongPitch", PERSISTENT},
{"LowerVolt", PERSISTENT}, {"LowerVolt", PERSISTENT},
{"MapTargetVelocities", PERSISTENT},
{"ModelUI", PERSISTENT}, {"ModelUI", PERSISTENT},
{"MTSCAggressiveness", PERSISTENT},
{"MTSCEnabled", PERSISTENT},
{"MuteDM", PERSISTENT}, {"MuteDM", PERSISTENT},
{"MuteDoor", PERSISTENT}, {"MuteDoor", PERSISTENT},
{"MuteOverheated", PERSISTENT}, {"MuteOverheated", PERSISTENT},

View File

@@ -559,3 +559,4 @@ tinygrad_repo/tinygrad/*.py
selfdrive/frogpilot/functions/conditional_experimental_mode.py selfdrive/frogpilot/functions/conditional_experimental_mode.py
selfdrive/frogpilot/functions/frogpilot_planner.py selfdrive/frogpilot/functions/frogpilot_planner.py
selfdrive/frogpilot/functions/map_turn_speed_controller.py

Binary file not shown.

After

Width:  |  Height:  |  Size: 63 KiB

View File

@@ -2,13 +2,14 @@ import cereal.messaging as messaging
import numpy as np import numpy as np
from openpilot.common.conversions import Conversions as CV from openpilot.common.conversions import Conversions as CV
from openpilot.common.numpy_fast import interp from openpilot.common.numpy_fast import clip, interp
from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, V_CRUISE_MAX from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, V_CRUISE_MAX
from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC
from openpilot.selfdrive.controls.lib.longitudinal_planner import A_CRUISE_MIN, A_CRUISE_MAX_VALS, A_CRUISE_MAX_BP, get_max_accel from openpilot.selfdrive.controls.lib.longitudinal_planner import A_CRUISE_MIN, A_CRUISE_MAX_VALS, A_CRUISE_MAX_BP, get_max_accel
from openpilot.selfdrive.modeld.constants import ModelConstants from openpilot.selfdrive.modeld.constants import ModelConstants
from openpilot.selfdrive.frogpilot.functions.conditional_experimental_mode import ConditionalExperimentalMode from openpilot.selfdrive.frogpilot.functions.conditional_experimental_mode import ConditionalExperimentalMode
from openpilot.selfdrive.frogpilot.functions.map_turn_speed_controller import MapTurnSpeedController
# Acceleration profiles - Credit goes to the DragonPilot team! # Acceleration profiles - Credit goes to the DragonPilot team!
# MPH = [0., 35, 35, 40, 40, 45, 45, 67, 67, 67, 123] # MPH = [0., 35, 35, 40, 40, 45, 45, 67, 67, 67, 123]
@@ -51,7 +52,9 @@ def calculate_lane_width(lane, current_lane, road_edge):
class FrogPilotPlanner: class FrogPilotPlanner:
def __init__(self, params): def __init__(self, params):
self.cem = ConditionalExperimentalMode() self.cem = ConditionalExperimentalMode()
self.mtsc = MapTurnSpeedController()
self.mtsc_target = 0
self.v_cruise = 0 self.v_cruise = 0
self.x_desired_trajectory = np.zeros(CONTROL_N) self.x_desired_trajectory = np.zeros(CONTROL_N)
@@ -68,7 +71,10 @@ class FrogPilotPlanner:
v_ego = carState.vEgo v_ego = carState.vEgo
# Acceleration profiles # Acceleration profiles
if self.acceleration_profile == 1: v_cruise_changed = (self.mtsc_target) + 1 < v_cruise # Use stock acceleration profiles to handle MTSC more precisely
if v_cruise_changed:
self.accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)]
elif self.acceleration_profile == 1:
self.accel_limits = [get_min_accel_eco_tune(v_ego), get_max_accel_eco_tune(v_ego)] self.accel_limits = [get_min_accel_eco_tune(v_ego), get_max_accel_eco_tune(v_ego)]
elif self.acceleration_profile in (2, 3): elif self.acceleration_profile in (2, 3):
self.accel_limits = [get_min_accel_sport_tune(v_ego), get_max_accel_sport_tune(v_ego)] self.accel_limits = [get_min_accel_sport_tune(v_ego), get_max_accel_sport_tune(v_ego)]
@@ -85,8 +91,16 @@ class FrogPilotPlanner:
self.x_desired_trajectory = self.x_desired_trajectory_full[:CONTROL_N] self.x_desired_trajectory = self.x_desired_trajectory_full[:CONTROL_N]
def update_v_cruise(self, carState, controlsState, modelData, enabled, v_cruise, v_ego): def update_v_cruise(self, carState, controlsState, modelData, enabled, v_cruise, v_ego):
# Pfeiferj's Map Turn Speed Controller
if self.map_turn_speed_controller:
self.mtsc_target = np.clip(self.mtsc.target_speed(v_ego, carState.aEgo), MIN_TARGET_V, v_cruise)
if self.mtsc_target == MIN_TARGET_V:
self.mtsc_target = v_cruise
else:
self.mtsc_target = v_cruise
v_ego_diff = max(carState.vEgoRaw - carState.vEgoCluster, 0) v_ego_diff = max(carState.vEgoRaw - carState.vEgoCluster, 0)
return v_cruise - v_ego_diff return min(v_cruise, self.mtsc_target) - v_ego_diff
def publish_lateral(self, sm, pm, DH): def publish_lateral(self, sm, pm, DH):
frogpilot_lateral_plan_send = messaging.new_message('frogpilotLateralPlan') frogpilot_lateral_plan_send = messaging.new_message('frogpilotLateralPlan')
@@ -103,6 +117,7 @@ class FrogPilotPlanner:
frogpilot_longitudinal_plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState']) frogpilot_longitudinal_plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState'])
frogpilotLongitudinalPlan = frogpilot_longitudinal_plan_send.frogpilotLongitudinalPlan frogpilotLongitudinalPlan = frogpilot_longitudinal_plan_send.frogpilotLongitudinalPlan
frogpilotLongitudinalPlan.adjustedCruise = float(min(self.mtsc_target) * (CV.MS_TO_KPH if self.is_metric else CV.MS_TO_MPH))
frogpilotLongitudinalPlan.conditionalExperimental = self.cem.experimental_mode frogpilotLongitudinalPlan.conditionalExperimental = self.cem.experimental_mode
frogpilotLongitudinalPlan.distances = self.x_desired_trajectory.tolist() frogpilotLongitudinalPlan.distances = self.x_desired_trajectory.tolist()
frogpilotLongitudinalPlan.redLight = bool(self.cem.red_light_detected) frogpilotLongitudinalPlan.redLight = bool(self.cem.red_light_detected)
@@ -140,3 +155,5 @@ class FrogPilotPlanner:
self.acceleration_profile = params.get_int("AccelerationProfile") if longitudinal_tune else 0 self.acceleration_profile = params.get_int("AccelerationProfile") if longitudinal_tune else 0
self.aggressive_acceleration = params.get_bool("AggressiveAcceleration") and longitudinal_tune self.aggressive_acceleration = params.get_bool("AggressiveAcceleration") and longitudinal_tune
self.increased_stopping_distance = params.get_int("StoppingDistance") * (1 if self.is_metric else CV.FOOT_TO_METER) if longitudinal_tune else 0 self.increased_stopping_distance = params.get_int("StoppingDistance") * (1 if self.is_metric else CV.FOOT_TO_METER) if longitudinal_tune else 0
self.map_turn_speed_controller = params.get_bool("MTSCEnabled")

View File

@@ -0,0 +1,152 @@
import json
import math
from openpilot.common.conversions import Conversions as CV
from openpilot.common.numpy_fast import interp
from openpilot.common.params import Params
params_memory = Params("/dev/shm/params")
R = 6373000.0 # approximate radius of earth in meters
TO_RADIANS = math.pi / 180
TO_DEGREES = 180 / math.pi
TARGET_JERK = -0.6 # m/s^3 There's some jounce limits that are not consistent so we're fudging this some
TARGET_ACCEL = -1.2 # m/s^2 should match up with the long planner limit
TARGET_OFFSET = 1.0 # seconds - This controls how soon before the curve you reach the target velocity. It also helps
# reach the target velocity when innacuracies in the distance modeling logic would cause overshoot.
# The value is multiplied against the target velocity to determine the additional distance. This is
# done to keep the distance calculations consistent but results in the offset actually being less
# time than specified depending on how much of a speed diffrential there is between v_ego and the
# target velocity.
def calculate_accel(t, target_jerk, a_ego):
return a_ego + target_jerk * t
def calculate_distance(t, target_jerk, a_ego, v_ego):
return t * v_ego + a_ego/2 * (t ** 2) + target_jerk/6 * (t ** 3)
def calculate_velocity(t, target_jerk, a_ego, v_ego):
return v_ego + a_ego * t + target_jerk/2 * (t ** 2)
# points should be in radians
# output is meters
def distance_to_point(ax, ay, bx, by):
a = math.sin((bx-ax)/2)*math.sin((bx-ax)/2) + math.cos(ax) * math.cos(bx)*math.sin((by-ay)/2)*math.sin((by-ay)/2)
c = 2 * math.atan2(math.sqrt(a), math.sqrt(1-a))
return R * c # in meters
class MapTurnSpeedController:
def __init__(self):
self.target_lat = 0.0
self.target_lon = 0.0
self.target_v = 0.0
def target_speed(self, v_ego, a_ego) -> float:
lat = 0.0
lon = 0.0
try:
position = json.loads(params_memory.get("LastGPSPosition"))
lat = position["latitude"]
lon = position["longitude"]
except: return 0.0
try:
target_velocities = json.loads(params_memory.get("MapTargetVelocities"))
except: return 0.0
min_dist = 1000
min_idx = 0
distances = []
# find our location in the path
for i in range(len(target_velocities)):
target_velocity = target_velocities[i]
tlat = target_velocity["latitude"]
tlon = target_velocity["longitude"]
d = distance_to_point(lat * TO_RADIANS, lon * TO_RADIANS, tlat * TO_RADIANS, tlon * TO_RADIANS)
distances.append(d)
if d < min_dist:
min_dist = d
min_idx = i
# only look at values from our current position forward
forward_points = target_velocities[min_idx:]
forward_distances = distances[min_idx:]
# find velocities that we are within the distance we need to adjust for
valid_velocities = []
for i in range(len(forward_points)):
target_velocity = forward_points[i]
tlat = target_velocity["latitude"]
tlon = target_velocity["longitude"]
tv = target_velocity["velocity"]
if tv > v_ego:
continue
d = forward_distances[i]
a_diff = (a_ego - TARGET_ACCEL)
accel_t = abs(a_diff / TARGET_JERK)
min_accel_v = calculate_velocity(accel_t, TARGET_JERK, a_ego, v_ego)
max_d = 0
if tv > min_accel_v:
# calculate time needed based on target jerk
a = 0.5 * TARGET_JERK
b = a_ego
c = v_ego - tv
t_a = -1 * ((b**2 - 4 * a * c) ** 0.5 + b) / 2 * a
t_b = ((b**2 - 4 * a * c) ** 0.5 - b) / 2 * a
if not isinstance(t_a, complex) and t_a > 0:
t = t_a
else:
t = t_b
if isinstance(t, complex):
continue
max_d = max_d + calculate_distance(t, TARGET_JERK, a_ego, v_ego)
else:
t = accel_t
max_d = calculate_distance(t, TARGET_JERK, a_ego, v_ego)
# calculate additional time needed based on target accel
t = abs((min_accel_v - tv) / TARGET_ACCEL)
max_d += calculate_distance(t, 0, TARGET_ACCEL, min_accel_v)
if d < max_d + tv * TARGET_OFFSET:
valid_velocities.append((float(tv), tlat, tlon))
# Find the smallest velocity we need to adjust for
min_v = 100.0
target_lat = 0.0
target_lon = 0.0
for tv, lat, lon in valid_velocities:
if tv < min_v:
min_v = tv
target_lat = lat
target_lon = lon
if self.target_v < min_v and not (self.target_lat == 0 and self.target_lon == 0):
for i in range(len(forward_points)):
target_velocity = forward_points[i]
tlat = target_velocity["latitude"]
tlon = target_velocity["longitude"]
tv = target_velocity["velocity"]
if tv > v_ego:
continue
if tlat == self.target_lat and tlon == self.target_lon and tv == self.target_v:
return float(self.target_v)
# not found so lets reset
self.target_v = 0.0
self.target_lat = 0.0
self.target_lon = 0.0
self.target_v = min_v
self.target_lat = target_lat
self.target_lon = target_lon
return min_v

View File

@@ -30,6 +30,8 @@ FrogPilotControlsPanel::FrogPilotControlsPanel(SettingsWindow *parent) : FrogPil
{"AccelerationProfile", "Acceleration Profile", "Change the acceleration rate to be either sporty or eco-friendly.", ""}, {"AccelerationProfile", "Acceleration Profile", "Change the acceleration rate to be either sporty or eco-friendly.", ""},
{"AggressiveAcceleration", "Aggressive Acceleration With Lead", "Increase acceleration aggressiveness when following a lead vehicle from a stop.", ""}, {"AggressiveAcceleration", "Aggressive Acceleration With Lead", "Increase acceleration aggressiveness when following a lead vehicle from a stop.", ""},
{"StoppingDistance", "Increased Stopping Distance", "Increase the stopping distance for a more comfortable stop.", ""}, {"StoppingDistance", "Increased Stopping Distance", "Increase the stopping distance for a more comfortable stop.", ""},
{"MTSCEnabled", "Map Turn Speed Control", "Slow down for anticipated curves detected by your downloaded maps.", "../frogpilot/assets/toggle_icons/icon_speed_map.png"},
}; };
for (const auto &[param, title, desc, icon] : controlToggles) { for (const auto &[param, title, desc, icon] : controlToggles) {

View File

@@ -493,7 +493,7 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : ""; QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "";
QString speedStr = QString::number(std::nearbyint(speed)); QString speedStr = QString::number(std::nearbyint(speed));
QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed)) : ""; QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : "";
// Draw outer box + border to contain set speed and speed limit // Draw outer box + border to contain set speed and speed limit
const int sign_margin = 12; const int sign_margin = 12;
@@ -512,7 +512,16 @@ void AnnotatedCameraWidget::drawHud(QPainter &p) {
int bottom_radius = has_eu_speed_limit ? 100 : 32; int bottom_radius = has_eu_speed_limit ? 100 : 32;
QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size);
if (reverseCruise) { if (is_cruise_set && cruiseAdjustment) {
float transition = qBound(0.0f, 4.0f * (cruiseAdjustment / setSpeed), 1.0f);
QColor min = whiteColor(75), max = redColor(75);
p.setPen(QPen(QColor::fromRgbF(
min.redF() + transition * (max.redF() - min.redF()),
min.greenF() + transition * (max.greenF() - min.greenF()),
min.blueF() + transition * (max.blueF() - min.blueF())
), 6));
} else if (reverseCruise) {
p.setPen(QPen(QColor(0, 150, 255), 6)); p.setPen(QPen(QColor(0, 150, 255), 6));
} else { } else {
p.setPen(QPen(whiteColor(75), 6)); p.setPen(QPen(whiteColor(75), 6));
@@ -1085,6 +1094,7 @@ void AnnotatedCameraWidget::updateFrogPilotWidgets(QPainter &p) {
conditionalSpeed = scene.conditional_speed; conditionalSpeed = scene.conditional_speed;
conditionalSpeedLead = scene.conditional_speed_lead; conditionalSpeedLead = scene.conditional_speed_lead;
conditionalStatus = scene.conditional_status; conditionalStatus = scene.conditional_status;
cruiseAdjustment = fmax((0.1 * fmax(setSpeed - scene.adjusted_cruise, 0) + 0.9 * cruiseAdjustment) - 1, 0);
customColors = scene.custom_colors; customColors = scene.custom_colors;
desiredFollow = scene.desired_follow; desiredFollow = scene.desired_follow;
experimentalMode = scene.experimental_mode; experimentalMode = scene.experimental_mode;

View File

@@ -143,6 +143,7 @@ private:
bool turnSignalRight; bool turnSignalRight;
bool useSI; bool useSI;
double maxAcceleration; double maxAcceleration;
float cruiseAdjustment;
float laneWidthLeft; float laneWidthLeft;
float laneWidthRight; float laneWidthRight;
int cameraView; int cameraView;

View File

@@ -252,6 +252,7 @@ static void update_state(UIState *s) {
scene.obstacle_distance_stock = frogpilotLongitudinalPlan.getSafeObstacleDistanceStock(); scene.obstacle_distance_stock = frogpilotLongitudinalPlan.getSafeObstacleDistanceStock();
scene.stopped_equivalence = frogpilotLongitudinalPlan.getStoppedEquivalenceFactor(); scene.stopped_equivalence = frogpilotLongitudinalPlan.getStoppedEquivalenceFactor();
} }
scene.adjusted_cruise = frogpilotLongitudinalPlan.getAdjustedCruise();
} }
if (sm.updated("liveLocationKalman")) { if (sm.updated("liveLocationKalman")) {
auto liveLocationKalman = sm["liveLocationKalman"].getLiveLocationKalman(); auto liveLocationKalman = sm["liveLocationKalman"].getLiveLocationKalman();

View File

@@ -193,6 +193,7 @@ typedef struct UIScene {
bool turn_signal_right; bool turn_signal_right;
bool unlimited_road_ui_length; bool unlimited_road_ui_length;
bool use_si; bool use_si;
float adjusted_cruise;
float lane_line_width; float lane_line_width;
float lane_width_left; float lane_width_left;
float lane_width_right; float lane_width_right;