Skip to content

Commit e018a41

Browse files
committed
fix pre-commit
Signed-off-by: Go Sakayori <go.sakayori@tier4.jp>
1 parent 3e06cc7 commit e018a41

File tree

14 files changed

+40
-36
lines changed

14 files changed

+40
-36
lines changed

control/autoware_smart_mpc_trajectory_follower/README.md

+14-14
Original file line numberDiff line numberDiff line change
@@ -211,21 +211,21 @@ It can be seen that the lateral deviation has improved significantly.
211211

212212
Here we have described wheel base, but the parameters that can be passed to the python simulator are as follows.
213213

214-
| Parameter | Type | Description |
215-
| ------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
216-
| steer_bias | float | steer bias [rad] |
217-
| steer_rate_lim | float | steer rate limit [rad/s] |
218-
| vel_rate_lim | float | acceleration limit [m/s^2] |
219-
| wheel_base | float | wheel base [m] |
220-
| steer_dead_band | float | steer dead band [rad] |
221-
| adaptive_gear_ratio_coef | list[float] | List of floats of length 6 specifying information on speed-dependent gear ratios from tire angle to steering wheel angle. |
222-
| acc_time_delay | float | acceleration time delay [s] |
223-
| steer_time_delay | float | steer time delay [s] |
224-
| acc_time_constant | float | acceleration time constant [s] |
225-
| steer_time_constant | float | steer time constant [s] |
214+
| Parameter | Type | Description |
215+
| ------------------------ | ----------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
216+
| steer_bias | float | steer bias [rad] |
217+
| steer_rate_lim | float | steer rate limit [rad/s] |
218+
| vel_rate_lim | float | acceleration limit [m/s^2] |
219+
| wheel_base | float | wheel base [m] |
220+
| steer_dead_band | float | steer dead band [rad] |
221+
| adaptive_gear_ratio_coef | list[float] | List of floats of length 6 specifying information on speed-dependent gear ratios from tire angle to steering wheel angle. |
222+
| acc_time_delay | float | acceleration time delay [s] |
223+
| steer_time_delay | float | steer time delay [s] |
224+
| acc_time_constant | float | acceleration time constant [s] |
225+
| steer_time_constant | float | steer time constant [s] |
226226
| accel_map_scale | float | Parameter that magnifies the corresponding distortion from acceleration input values to actual acceleration realizations. <br> Correspondence information is kept in `control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/accel_map.csv`. |
227-
| acc_scaling | float | acceleration scaling |
228-
| steer_scaling | float | steer scaling |
227+
| acc_scaling | float | acceleration scaling |
228+
| steer_scaling | float | steer scaling |
229229

230230
For example, to give the simulation side 0.01 [rad] of steer bias and 0.001 [rad] of steer dead band, edit the `sim_setting.json` as follows.
231231

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/python_simulator.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -18,14 +18,14 @@
1818
import datetime
1919
import os
2020

21+
from autoware_smart_mpc_trajectory_follower.scripts import drive_controller
22+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2123
import matplotlib.pyplot as plt
2224
from numba import njit
2325
import numpy as np
2426
import pandas as pd
2527
import scipy.interpolate
2628
import simplejson as json
27-
from autoware_smart_mpc_trajectory_follower.scripts import drive_controller
28-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2929

3030
print("\n\n### import python_simulator.py ###")
3131

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_python_simulator.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model
1516
import numpy as np
1617
import python_simulator
17-
from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model
1818

1919
initial_error = np.array(
2020
[0.001, 0.03, 0.01, -0.001, 0, 2 * python_simulator.measurement_steer_bias]

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/python_simulator/run_sim.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,9 @@
2323
import traceback
2424
from typing import Dict
2525

26+
from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model
2627
import numpy as np
2728
import python_simulator
28-
from autoware_smart_mpc_trajectory_follower.training_and_data_check import train_drive_NN_model
2929

3030
parser = argparse.ArgumentParser()
3131
parser.add_argument("--param_name", default=None)

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_GP.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616

1717
from functools import partial
1818

19+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
1920
from numba import njit
2021
import numpy as np
21-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2222

2323
sqrt_mpc_time_step = np.sqrt(drive_functions.mpc_time_step)
2424

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,9 @@
1313
# limitations under the License.
1414

1515

16-
import numpy as np
1716
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
1817
from autoware_smart_mpc_trajectory_follower.scripts import proxima_calc
18+
import numpy as np
1919
import torch
2020
from torch import nn
2121

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -21,14 +21,14 @@
2121
import threading
2222
import time
2323

24-
import numpy as np
25-
import scipy.interpolate # type: ignore
26-
from sklearn.preprocessing import PolynomialFeatures
2724
from autoware_smart_mpc_trajectory_follower.scripts import drive_GP
2825
from autoware_smart_mpc_trajectory_follower.scripts import drive_NN
2926
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
3027
from autoware_smart_mpc_trajectory_follower.scripts import drive_iLQR
3128
from autoware_smart_mpc_trajectory_follower.scripts import drive_mppi
29+
import numpy as np
30+
import scipy.interpolate # type: ignore
31+
from sklearn.preprocessing import PolynomialFeatures
3232
import torch
3333

3434
ctrl_index_for_polynomial_reg = np.concatenate(

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py

+3-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,9 @@
3131
with open(package_path_json, "r") as file:
3232
package_path = json.load(file)
3333

34-
mpc_param_path = package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml"
34+
mpc_param_path = (
35+
package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml"
36+
)
3537
with open(mpc_param_path, "r") as yml:
3638
mpc_param = yaml.safe_load(yml)
3739

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_iLQR.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@
2121
import time
2222
from typing import Callable
2323

24+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2425
from numba import njit
2526
import numpy as np
26-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2727

2828
index_cost = np.concatenate(
2929
(

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_mppi.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616

1717
from typing import Callable
1818

19+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
1920
from numba import njit
2021
import numpy as np
21-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2222

2323
index_cost = np.concatenate(
2424
(

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222
from autoware_control_msgs.msg import Control
2323
from autoware_planning_msgs.msg import Trajectory
2424
from autoware_planning_msgs.msg import TrajectoryPoint
25+
from autoware_smart_mpc_trajectory_follower.scripts import drive_controller
26+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2527
from autoware_vehicle_msgs.msg import SteeringReport
2628
from builtin_interfaces.msg import Duration
2729
from geometry_msgs.msg import AccelWithCovarianceStamped
@@ -34,8 +36,6 @@
3436
import scipy.interpolate
3537
from scipy.spatial.transform import Rotation as R
3638
from scipy.spatial.transform import Slerp
37-
from autoware_smart_mpc_trajectory_follower.scripts import drive_controller
38-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
3939
from std_msgs.msg import String
4040
from tier4_debug_msgs.msg import BoolStamped
4141
from tier4_debug_msgs.msg import Float32MultiArrayStamped

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/add_training_data_from_csv.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,11 +23,11 @@
2323
import os
2424
from pathlib import Path
2525

26+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
2627
import numpy as np
2728
import scipy.interpolate
2829
from scipy.ndimage import gaussian_filter
2930
from scipy.spatial.transform import Rotation
30-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
3131

3232

3333
def data_smoothing(data: np.ndarray, sigma: float) -> np.ndarray:

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/training_and_data_check/train_drive_NN_model.py

+5-3
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,15 @@
1515
# cspell: ignore optim savez suptitle
1616

1717
"""Class for training neural nets from driving data."""
18+
from autoware_smart_mpc_trajectory_follower.scripts import drive_NN
19+
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
20+
from autoware_smart_mpc_trajectory_follower.training_and_data_check import (
21+
add_training_data_from_csv,
22+
)
1823
import matplotlib.pyplot as plt
1924
import numpy as np
2025
from sklearn import linear_model
2126
from sklearn.preprocessing import PolynomialFeatures
22-
from autoware_smart_mpc_trajectory_follower.scripts import drive_NN
23-
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
24-
from autoware_smart_mpc_trajectory_follower.training_and_data_check import add_training_data_from_csv
2527
import torch
2628
from torch import nn
2729
from torch.utils.data import DataLoader

control/autoware_smart_mpc_trajectory_follower/setup.py

+4-4
Original file line numberDiff line numberDiff line change
@@ -17,15 +17,15 @@
1717
json.dump(package_path, f)
1818
build_cpp_command = "g++ -Ofast -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) "
1919
build_cpp_command += "autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp "
20-
build_cpp_command += (
21-
"-o autoware_smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) "
22-
)
20+
build_cpp_command += "-o autoware_smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) "
2321
build_cpp_command += "-lrt -I/usr/include/eigen3"
2422
os.system(build_cpp_command)
2523

2624
so_path = (
2725
"scripts/"
28-
+ glob.glob("autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[-1]
26+
+ glob.glob("autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[
27+
-1
28+
]
2929
)
3030
setup(
3131
name="smart_mpc_trajectory_follower",

0 commit comments

Comments
 (0)