Skip to content

Commit

Permalink
feat: add accel and pedal maps configuration (#4)
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
xmfcx authored Sep 20, 2024
1 parent efe9726 commit 467df73
Show file tree
Hide file tree
Showing 6 changed files with 67 additions and 1 deletion.
2 changes: 2 additions & 0 deletions awsim_labs_vehicle_launch/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,7 @@ find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_package(INSTALL_TO_SHARE
config
data
launch
)
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
/**:
ros__parameters:
csv_path_accel_map: $(find-pkg-share awsim_labs_vehicle_launch)/data/accel_map.csv
csv_path_brake_map: $(find-pkg-share awsim_labs_vehicle_launch)/data/brake_map.csv
csv_path_steer_map: $(find-pkg-share awsim_labs_vehicle_launch)/data/steer_map.csv
convert_accel_cmd: true
convert_brake_cmd: true
convert_steer_cmd: false
use_steer_ff: true
use_steer_fb: true
is_debugging: false
max_throttle: 0.4
max_brake: 0.8
max_steer: 10.0
min_steer: -10.0
steer_pid:
kp: 150.0
ki: 15.0
kd: 0.0
max: 8.0
min: -8.0
max_p: 8.0
min_p: -8.0
max_i: 8.0
min_i: -8.0
max_d: 0.0
min_d: 0.0
invalid_integration_decay: 0.97
convert_steer_cmd_method: "vgr" # "vgr" or "steer_map"
vgr_coef_a: 15.713
vgr_coef_b: 0.053
vgr_coef_c: 0.042
convert_actuation_to_steering_status: false
7 changes: 7 additions & 0 deletions awsim_labs_vehicle_launch/data/accel_map.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
0,0.300,-0.050,-0.297,-0.390,-0.400,-0.410,-0.420,-0.440,-0.573,-0.574,-0.575
0.100,0.600,0.420,0.240,0.064,-0.266,-0.267,-0.268,-0.269,-0.270,-0.290,-0.291
0.200,0.642,0.421,0.241,0.065,0.052,0.051,-0.029,-0.030,-0.065,-0.066,-0.067
0.300,1.420,0.636,0.635,0.587,0.586,0.585,0.584,0.583,0.582,0.186,0.185
0.400,1.964,1.338,1.324,1.323,1.322,1.321,1.320,1.239,0.900,0.899,0.898
0.500,2.620,1.339,1.335,1.324,1.323,1.922,2.007,1.938,1.874,1.406,1.454
10 changes: 10 additions & 0 deletions awsim_labs_vehicle_launch/data/brake_map.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
default,0,1.39,2.78,4.17,5.56,6.94,8.33,9.72,11.11,12.5,13.89
0,0.3,-0.05,-0.297,-0.39,-0.4,-0.531,-1.115,-1.116,-1.117,-1.118,-1.119
0.1,0.117,-0.487,-0.825,-1.004,-1.114,-1.115,-1.116,-1.117,-1.118,-1.119,-1.12
0.2,-0.821,-1.374,-1.606,-1.77,-2.225,-2.226,-2.227,-2.228,-2.231,-2.232,-2.233
0.3,-1.473,-1.963,-2.23,-2.376,-2.695,-2.696,-2.697,-2.698,-2.699,-2.7,-2.701
0.4,-1.959,-2.496,-2.665,-2.856,-3.034,-3.035,-3.036,-3.037,-3.038,-3.039,-3.04
0.5,-2.181,-2.87,-3.015,-3.139,-3.3,-3.301,-3.302,-3.303,-3.304,-3.305,-3.306
0.6,-2.182,-2.871,-3.016,-3.14,-3.301,-3.302,-3.303,-3.304,-3.305,-3.306,-3.307
0.7,-2.183,-2.872,-3.017,-3.141,-3.302,-3.303,-3.304,-3.305,-3.306,-3.307,-3.308
0.8,-2.201,-2.873,-3.018,-3.142,-3.303,-3.304,-3.305,-3.306,-3.307,-3.308,-3.309
14 changes: 14 additions & 0 deletions awsim_labs_vehicle_launch/data/steer_map.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
default,-0.6,-0.5,-0.4,-0.3,-0.2,-0.1,0,0.1,0.2,0.3,0.4,0.5,0.6
-12,-0.29,-0.3234236132,-0.3468991362,-0.37274847,-0.4288688461,-0.4696573,-0.4781014157,-0.49,-0.51,-0.52,-0.53,-0.54,-0.55
-10,-0.2,-0.2451308686,-0.2667782734,-0.3090752469,-0.3575200568,-0.3874868999,-0.4041493831,-0.42,-0.43,-0.44,-0.45,-0.46,-0.47
-8,-0.1,-0.1586739777,-0.2020698818,-0.2317654357,-0.2778998646,-0.3029839842,-0.3188172953,-0.32,-0.33,-0.34,-0.35,-0.36,-0.37
-6,-0.0404761584,-0.0806574159,-0.1208386734,-0.1559621241,-0.1888907059,-0.210790018,-0.2322336736,-0.24,-0.25,-0.26,-0.27,-0.28,-0.29
-4,0.01,-0.01428569928,-0.04,-0.06805018099,-0.09718925222,-0.1189509092,-0.1361293637,-0.14,-0.153044463,-0.1688321844,-0.18,-0.2,-0.22
-2,0.06,0.05,0.03,0.01,-0.006091655083,-0.03546033903,-0.05319488695,-0.06097627388,-0.07576251508,-0.09165178816,-0.1,-0.12,-0.14
0,0.11,0.09,0.07,0.05,0.03,0.01,-0.0004106386541,-0.01,-0.03,-0.05,-0.07,-0.09,-0.11
2,0.15,0.13,0.11,0.09,0.07812978496,0.06023545297,0.04386326928,0.02314813566,0.003779338416,-0.01390526686,-0.0324840879,-0.05106290894,-0.06964172998
4,0.24,0.22,0.2,0.1839795042,0.1649754952,0.1455879759,0.1274837062,0.1020632549,0.0861964856,0.06971503353,0.04541294018,0.01308869356,-0.01923555307
6,0.33,0.31,0.29,0.274963497,0.2447295892,0.2337353319,0.2126138313,0.1767700907,0.1578757866,0.1440584148,0.1136331403,0.0827443595,0.05185557872
8,0.43,0.41,0.39,0.3714915121,0.3299578073,0.3156403746,0.2997845963,0.2500495071,0.2339668568,0.2153133621,0.1815127859,0.156071251,0.1306297162
10,0.5,0.49,0.48,0.4629455165,0.4210353203,0.3977027236,0.3865034288,0.3250957262,0.312237913,0.2885123051,0.2474220915,0.2123900615,0.1773580315
12,0.56,0.54,0.53,0.5151036525,0.5046070554,0.4897214196,0.4687756354,0.4036994672,0.3812674227,0.3496883008,0.32482655,0.2783538423,0.2318811345
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<arg name="output_actuation_cmd" default="/control/command/actuation_cmd"/>
<arg name="output_steering_status" default="/vehicle/status/steering_status"/>
<!-- Parameter -->
<arg name="config_file" default="$(find-pkg-share autoware_raw_vehicle_cmd_converter)/config/raw_vehicle_cmd_converter.param.yaml"/>
<arg name="config_file" default="$(find-pkg-share awsim_labs_vehicle_launch)/config/raw_vehicle_cmd_converter/raw_vehicle_cmd_converter.param.yaml"/>

<node pkg="autoware_raw_vehicle_cmd_converter" exec="autoware_raw_vehicle_cmd_converter_node" name="raw_vehicle_cmd_converter" output="screen">
<param from="$(var config_file)" allow_substs="true"/>
Expand Down

0 comments on commit 467df73

Please sign in to comment.