Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add cost to long plan change for smoother lag comp #22923

Merged
merged 9 commits into from
Nov 17, 2021
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
29 changes: 20 additions & 9 deletions selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,15 +24,17 @@

X_DIM = 3
U_DIM = 1
COST_E_DIM = 4
PARAM_DIM= 4
COST_E_DIM = 5
COST_DIM = COST_E_DIM + 1
CONSTR_DIM = 4

X_EGO_OBSTACLE_COST = 3.
V_EGO_COST = 0.
X_EGO_COST = 0.
V_EGO_COST = 0.
A_EGO_COST = 0.
J_EGO_COST = 10.
J_EGO_COST = 5.0
A_CHANGE_COST = .5
DANGER_ZONE_COST = 100.
CRASH_DISTANCE = .5
LIMIT_COST = 1e6
Expand Down Expand Up @@ -85,7 +87,8 @@ def gen_long_model():
x_obstacle = SX.sym('x_obstacle')
a_min = SX.sym('a_min')
a_max = SX.sym('a_max')
model.p = vertcat(a_min, a_max, x_obstacle)
prev_a = SX.sym('prev_a')
model.p = vertcat(a_min, a_max, x_obstacle, prev_a)

# dynamics model
f_expl = vertcat(v_ego, a_ego, j_ego)
Expand Down Expand Up @@ -118,6 +121,7 @@ def gen_long_mpc_solver():

a_min, a_max = ocp.model.p[0], ocp.model.p[1]
x_obstacle = ocp.model.p[2]
prev_a = ocp.model.p[3]

ocp.cost.yref = np.zeros((COST_DIM, ))
ocp.cost.yref_e = np.zeros((COST_E_DIM, ))
Expand All @@ -132,6 +136,7 @@ def gen_long_mpc_solver():
x_ego,
v_ego,
a_ego,
20*(a_ego - prev_a),
j_ego]
ocp.model.cost_y_expr = vertcat(*costs)
ocp.model.cost_y_expr_e = vertcat(*costs[:-1])
Expand All @@ -148,7 +153,7 @@ def gen_long_mpc_solver():

x0 = np.zeros(X_DIM)
ocp.constraints.x0 = x0
ocp.parameter_values = np.array([-1.2, 1.2, 0.0])
ocp.parameter_values = np.array([-1.2, 1.2, 0.0, 0.0])

# We put all constraint cost weights to 0 and only set them at runtime
cost_weights = np.zeros(CONSTR_DIM)
Expand Down Expand Up @@ -198,14 +203,15 @@ def reset(self):
self.solver = AcadosOcpSolverFast('long', N, EXPORT_DIR)
self.v_solution = [0.0 for i in range(N+1)]
self.a_solution = [0.0 for i in range(N+1)]
self.prev_a = self.a_solution
self.j_solution = [0.0 for i in range(N)]
self.yref = np.zeros((N+1, COST_DIM))
for i in range(N):
self.solver.cost_set(i, "yref", self.yref[i])
self.solver.cost_set(N, "yref", self.yref[N][:COST_E_DIM])
self.x_sol = np.zeros((N+1, X_DIM))
self.u_sol = np.zeros((N,1))
self.params = np.zeros((N+1,3))
self.params = np.zeros((N+1, PARAM_DIM))
for i in range(N+1):
self.solver.set(i, 'x', np.zeros(X_DIM))
self.last_cloudlog_t = 0
Expand All @@ -222,8 +228,9 @@ def set_weights(self):
self.set_weights_for_lead_policy()

def set_weights_for_lead_policy(self):
W = np.asfortranarray(np.diag([X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, J_EGO_COST]))
W = np.asfortranarray(np.diag([X_EGO_OBSTACLE_COST, X_EGO_COST, V_EGO_COST, A_EGO_COST, A_CHANGE_COST, J_EGO_COST]))
for i in range(N):
W[4,4] = A_CHANGE_COST * np.interp(T_IDXS[i], [0.0, 1.0, 2.0], [1.0, 1.0, 0.0])
self.solver.cost_set(i, 'W', W)
# Setting the slice without the copy make the array not contiguous,
# causing issues with the C interface.
Expand All @@ -235,7 +242,7 @@ def set_weights_for_lead_policy(self):
self.solver.cost_set(i, 'Zl', Zl)

def set_weights_for_xva_policy(self):
W = np.asfortranarray(np.diag([0., 10., 1., 10., 1.]))
W = np.asfortranarray(np.diag([0., 10., 1., 10., 0.0, 1.]))
for i in range(N):
self.solver.cost_set(i, 'W', W)
# Setting the slice without the copy make the array not contiguous,
Expand Down Expand Up @@ -320,6 +327,7 @@ def update(self, carstate, radarstate, v_cruise):
x_obstacles = np.column_stack([lead_0_obstacle, lead_1_obstacle, cruise_obstacle])
self.source = SOURCES[np.argmin(x_obstacles[0])]
self.params[:,2] = np.min(x_obstacles, axis=1)
self.params[:,3] = np.copy(self.prev_a)

self.run()
if (np.any(lead_xv_0[:,0] - self.x_sol[:,0] < CRASH_DISTANCE) and
Expand All @@ -339,7 +347,8 @@ def update_with_xva(self, x, v, a):
self.accel_limit_arr[:,1] = 10.
x_obstacle = 1e5*np.ones((N+1))
self.params = np.concatenate([self.accel_limit_arr,
x_obstacle[:,None]], axis=1)
x_obstacle[:,None],
self.prev_a], axis=1)
self.run()


Expand All @@ -358,6 +367,8 @@ def run(self):
self.a_solution = self.x_sol[:,2]
self.j_solution = self.u_sol[:,0]

self.prev_a = interp(T_IDXS + 0.05, T_IDXS, self.a_solution)

t = sec_since_boot()
if self.solution_status != 0:
if t > self.last_cloudlog_t + 5.0:
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/test/longitudinal_maneuvers/test_longitudinal.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@
speed_lead_values=[20., 20., 0.],
prob_lead_values=[0., 1., 1.],
cruise_values=[20., 20., 20.],
breakpoints=[2., 2.01, 8.51],
breakpoints=[2., 2.01, 8.8],
),
Maneuver(
"approach stopped car at 20m/s",
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/test/process_replay/ref_commit
Original file line number Diff line number Diff line change
@@ -1 +1 @@
8b929f005a01a4207e218510512ae72689dd2565
6540e8c5a765975fd292b1efdef97b2d6391fa9c