Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions common/params_keys.h
Original file line number Diff line number Diff line change
Expand Up @@ -278,6 +278,7 @@ inline static std::unordered_map<std::string, ParamKeyAttributes> keys = {
{"LaneChangeNeedTorque", {PERSISTENT, INT, "0"}},
{"LaneChangeDelay", {PERSISTENT, INT, "0"}},
{"LaneChangeBsd", {PERSISTENT, INT, "0"}},
{"LaneLineCheck", {PERSISTENT, INT, "0"}},
{"MaxAngleFrames", {PERSISTENT, INT, "89"}},

{"SoftHoldMode", {PERSISTENT, INT, "0"}},
Expand Down
15 changes: 13 additions & 2 deletions opendbc_repo/opendbc/car/hyundai/hyundaicanfd.py
Original file line number Diff line number Diff line change
Expand Up @@ -644,6 +644,9 @@ def create_ccnc_messages(CP, packer, CAN, frame, CC, CS, hud_control,
ret = []

md = CS.MD
if not hasattr(create_ccnc_messages, '_lane_line_check') or frame % 100 == 0:
create_ccnc_messages._lane_line_check = Params().get_int("LaneLineCheck")
lane_line_check = create_ccnc_messages._lane_line_check
desire, lane_changing = _get_desire_and_lane_changing(md)

if CP.flags & HyundaiFlags.CAMERA_SCC.value:
Expand Down Expand Up @@ -743,14 +746,22 @@ def create_ccnc_messages(CP, packer, CAN, frame, CC, CS, hud_control,
values["LANELINE_CURVATURE_DIRECTION"] = 1 if curvature < 0 and lat_active else 0

lane_color = 6 if md is not None and md.meta.laneChangeAvailableLeft else 2
lane_color = 4 if CS.out.leftLaneLine >= 20 or CS.out.leftBlindspot else lane_color
if lane_line_check >= 1:
lane_line_warn_left = CS.out.leftLaneLine % 10 not in (0, 5) # 실선이면 주황
else:
lane_line_warn_left = CS.out.leftLaneLine >= 20 # 노란색이면 주황
lane_color = 4 if lane_line_warn_left or CS.out.leftBlindspot else lane_color
if hud_control.leftLaneDepart:
values["LANELINE_LEFT"] = 4 if (frame // 50) % 2 == 0 else 1
else:
values["LANELINE_LEFT"] = lane_color if hud_control.leftLaneVisible else 0

lane_color = 6 if md is not None and md.meta.laneChangeAvailableRight else 2
lane_color = 4 if CS.out.rightLaneLine >= 20 or CS.out.rightBlindspot else lane_color
if lane_line_check >= 1:
lane_line_warn_right = CS.out.rightLaneLine % 10 not in (0, 5)
else:
lane_line_warn_right = CS.out.rightLaneLine >= 20
lane_color = 4 if lane_line_warn_right or CS.out.rightBlindspot else lane_color
if hud_control.rightLaneDepart:
values["LANELINE_RIGHT"] = 4 if (frame // 50) % 2 == 0 else 1
else:
Expand Down
16 changes: 16 additions & 0 deletions selfdrive/carrot_settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -1649,6 +1649,22 @@
"ctitle": "变道盲点监测 (BSD)",
"cdescr": "0: BSD 检测 (允许转向力矩), 1: 阻止转向力矩, -1: 忽略 BSD"
},
{
"group": "조향일반",
"name": "LaneLineCheck",
"title": "차선변경 차선판단",
"descr": "0: 색상+타입(노란선차단)\n1: 타입만(점선/실선)\n2: 타입만+실선토크override",
"egroup": "LAT",
"etitle": "LaneChange LineCheck",
"edescr": "0: Color+Type(block yellow), 1: Type only, 2: Type+torque override solid",
"min": 0,
"max": 2,
"default": 0,
"unit": 1,
"cgroup": "转向",
"ctitle": "变道车道判断",
"cdescr": "0: 颜色+类型(黄线阻止), 1: 仅类型(虚线/实线), 2: 仅类型+实线扭矩override"
},
{
"group": "시작",
"name": "HapticFeedbackWhenSpeedCamera",
Expand Down
23 changes: 19 additions & 4 deletions selfdrive/controls/lib/desire_helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ def __init__(self):
# params
self.laneChangeNeedTorque = 0
self.laneChangeBsd = 0
self.laneLineCheck = 0
self.laneChangeDelay = 0.0
self.modelTurnSpeedFactor = 0.0
self.model_turn_speed = 200.0
Expand All @@ -76,6 +77,7 @@ def _update_params_periodic(self):
if self.frame % 100 == 0:
self.laneChangeNeedTorque = self.params.get_int("LaneChangeNeedTorque")
self.laneChangeBsd = self.params.get_int("LaneChangeBsd")
self.laneLineCheck = self.params.get_int("LaneLineCheck")
self.laneChangeDelay = self.params.get_float("LaneChangeDelay") * 0.1
self.modelTurnSpeedFactor = self.params.get_float("ModelTurnSpeedFactor") * 0.1

Expand Down Expand Up @@ -191,8 +193,14 @@ def _process_sides(self, carstate, modeldata, radarState):
self.right.update_obstacles(v_ego, radarState.leadRight, carstate.rightBlindspot, ignore_bsd, bsd_hold_sec=2.0)

# compute available (include BSD+object)
self.left.compute_lane_change_available(lane_line_info_lt_20=(self.left.lane_line_info_raw < 20), ignore_bsd=ignore_bsd)
self.right.compute_lane_change_available(lane_line_info_lt_20=(self.right.lane_line_info_raw < 20), ignore_bsd=ignore_bsd)
if self.laneLineCheck >= 1:
left_line_ok = self.left.lane_line_info_mod in (0, 5)
right_line_ok = self.right.lane_line_info_mod in (0, 5)
else:
left_line_ok = self.left.lane_line_info_raw < 20
right_line_ok = self.right.lane_line_info_raw < 20
self.left.compute_lane_change_available(lane_line_info_lt_20=left_line_ok, ignore_bsd=ignore_bsd)
self.right.compute_lane_change_available(lane_line_info_lt_20=right_line_ok, ignore_bsd=ignore_bsd)

self.left.update_triggers()
self.right.update_triggers()
Expand Down Expand Up @@ -350,10 +358,17 @@ def update(self, carstate, modeldata, lateral_active, lane_change_prob, carrotMa
# 차선변경 시작 조건:
# - side.lane_change_available는 BSD+object 포함(요구사항)
# - 하지만 BSD 중에도 torque override 허용해야 하므로, BSD 분기를 별도로 둠(원본 동작 유지)
start_gate = (side.lane_change_available_geom and self.lane_change_delay == 0) or side.lane_line_info_edge_detect
# LaneLineCheck=2: 실선에서도 토크 override 허용
solid_line_blocked = (self.laneLineCheck >= 2) and (not side.lane_change_available_geom) and \
(side.lane_available or side.edge_available)
start_gate = (side.lane_change_available_geom and self.lane_change_delay == 0) or \
side.lane_line_info_edge_detect or solid_line_blocked

if start_gate:
if bsd_active:
if solid_line_blocked:
if torque_applied and not (bsd_active and block_lanechange_bsd):
self.lane_change_state = LaneChangeState.laneChangeStarting
elif bsd_active:
if torque_applied and (not block_lanechange_bsd):
self.lane_change_state = LaneChangeState.laneChangeStarting
elif self.laneChangeNeedTorque > 0 or self.next_lane_change:
Expand Down
1 change: 1 addition & 0 deletions selfdrive/ui/qt/offroad/settings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -698,6 +698,7 @@ CarrotPanel::CarrotPanel(QWidget* parent) : QWidget(parent) {
latLongToggles->addItem(new CValueControl("LaneChangeNeedTorque", tr("LaneChange need torque"), tr("-1:Disable lanechange, 0: no need torque, 1:need torque"), -1, 1, 1));
latLongToggles->addItem(new CValueControl("LaneChangeDelay", tr("LaneChange delay"), tr("x0.1sec"), 0, 100, 5));
latLongToggles->addItem(new CValueControl("LaneChangeBsd", tr("LaneChange Bsd"), tr("-1:ignore bsd, 0:BSD detect, 1: block steer torque"), -1, 1, 1));
latLongToggles->addItem(new CValueControl("LaneLineCheck", tr("LaneChange LineCheck"), tr("0:Color+Type, 1:Type only, 2:Type+torque override solid"), 0, 2, 1));
latLongToggles->addItem(new CValueControl("CustomSR", tr("LAT: SteerRatiox0.1(0)"), tr("Custom SteerRatio"), 0, 300, 1));
latLongToggles->addItem(new CValueControl("SteerRatioRate", tr("LAT: SteerRatioRatex0.01(100)"), tr("SteerRatio apply rate"), 30, 170, 1));
latLongToggles->addItem(new CValueControl("PathOffset", tr("LAT: PathOffset"), tr("(-)left, (+)right"), -150, 150, 1));
Expand Down