Skip to content

Commit

Permalink
[pre-commit.ci] auto fixes from pre-commit.com hooks
Browse files Browse the repository at this point in the history
for more information, see https://pre-commit.ci
  • Loading branch information
pre-commit-ci[bot] committed May 27, 2024
1 parent 5fd60cf commit 28facb1
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion nodes/control_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ def calc_target_index(self, state, cx, cy, cyaw):
dx_vec = fx - np.asarray(cx).reshape([-1, 1])
dy_vec = fy - np.asarray(cy).reshape([-1, 1])
dist = np.hstack([dx_vec, dy_vec])
dist_2 = np.sum(dist ** 2, axis=1)
dist_2 = np.sum(dist**2, axis=1)
target_idx = np.argmin(dist_2)

# Project RMS error onto front axle vector
Expand Down
2 changes: 1 addition & 1 deletion nodes/planning_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ def create_trajectory(
Z = np.array([lane_coeff.W, lane_coeff.Y_offset, lane_coeff.dPhi, lane_coeff.c0])

for i, u in enumerate(x):
u2 = u ** 2
u2 = u**2
y[i] = np.dot(np.array([0, -1, -u, 0.5 * u2]), Z)

tran_mat = tf_listener.asMatrix("map", lane_coeff.header)
Expand Down

0 comments on commit 28facb1

Please sign in to comment.