Skip to content

Commit 893eed2

Browse files
Merge pull request #157 from krishauser/s2025_Simulation_vikram
Gazebo - GEMStack Integration
2 parents 3f183be + 3d7bdb1 commit 893eed2

34 files changed

Lines changed: 1581 additions & 638 deletions

.gitignore

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -165,3 +165,15 @@ cython_debug/
165165
# and can be added to the global gitignore or merged into this file. For a more nuclear
166166
# option (not recommended) you can uncomment the following to ignore the entire idea folder.
167167
#.idea/
168+
169+
# ZED run files
170+
**/*.run
171+
.vscode/
172+
setup/zed_sdk.run
173+
cuda/
174+
homework/yolov8n.pt
175+
homework/yolo11n.pt
176+
GEMstack/knowledge/detection/yolov8n.pt
177+
GEMstack/knowledge/detection/yolo11n.pt
178+
yolov8n.pt
179+
yolo11n.pt
Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
calibration_date: "2023-08-31" # Date of calibration YYYY-MM-DD
2+
reference: rear_axle_center # rear axle center
3+
rear_axle_height: 0.273 # height of rear axle center above flat ground
4+
gnss_location: [1.1,0.0,0.3] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/vehicle_drivers/gem_gnss_control/scripts/gem_gnss_tracker_stanley_rtk.py. Note conflict with pure pursuit location?
5+
gnss_yaw: 0.0 # radians
6+
front_radar_location: [1.45,0,0.07] # meters, taken from https://github.com/hangcui1201/POLARIS_GEM_e2_Real/blob/main/platform_launch/launch/white_e2/platform.launch
7+
top_lidar: !include "gem_e2_velodyne.yaml"
8+
front_camera: !include "gem_e2_zed.yaml"
9+
T_frontcamera_vehicle:
10+
- - 0.04979815921110274
11+
- -0.02889308605338095
12+
- 0.998341277156963
13+
- 0.6874899022540225
14+
- - -0.9986898492450907
15+
- 0.010343220052680617
16+
- 0.05011489006575621
17+
- -0.006750728511462573
18+
- - -0.011774038000135968
19+
- -0.9995289850272167
20+
- -0.02834016107658961
21+
- -0.07694233627246522
22+
- - 0.0
23+
- 0.0
24+
- 0.0
25+
- 1.0
26+
T_toplidar_frontcamera:
27+
- - 0.029096143490519977
28+
- -0.9995463314295703
29+
- -0.007781115579835407
30+
- -0.045768971801312515
31+
- - -0.005777780139254174
32+
- 0.007616104089319731
33+
- -0.999954305063568
34+
- -0.3868171492765085
35+
- - 0.9995599190096819
36+
- 0.02913977151915098
37+
- -0.005553559684576381
38+
- -0.6975440651652165
39+
- - 0.0
40+
- 0.0
41+
- 0.0
42+
- 1.0
43+
T_toplidar_vehicle:
44+
- - 0.9995177984237671
45+
- -0.020904183387756348
46+
- 0.022959932684898376
47+
- 0.0
48+
- - 0.020975051447749138
49+
- 0.9997758865356445
50+
- -0.0028501423075795174
51+
- 0.0
52+
- - -0.0228952094912529
53+
- 0.003330353880301118
54+
- 0.9997323155403137
55+
- 0.33000001311302185
56+
- - 0.0
57+
- 0.0
58+
- 0.0
59+
- 1.0
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
date: '2025-02-25 22:31:02.057447'
2+
calibration_type: absolute_vehicle_calibration
3+
gnss_location:
4+
- 1.1
5+
- 0
6+
- 1.62
7+
gnss_yaw: 0.0
8+
rear_axle_height: 0.33
9+
reference: rear_axle_center
10+
vehicle: gem_e4
11+
top_lidar: !include "gem_e4_ouster.yaml"
12+
front_camera: !include "gem_e4_oak.yaml"
13+
gnss_reference_point: [40.114001, -88.228837]
14+
T_frontcamera_vehicle:
15+
- - 0.04979815921110274
16+
- -0.02889308605338095
17+
- 0.998341277156963
18+
- 0.6874899022540225
19+
- - -0.9986898492450907
20+
- 0.010343220052680617
21+
- 0.05011489006575621
22+
- -0.006750728511462573
23+
- - -0.011774038000135968
24+
- -0.9995289850272167
25+
- -0.02834016107658961
26+
- -0.07694233627246522
27+
- - 0.0
28+
- 0.0
29+
- 0.0
30+
- 1.0
31+
T_toplidar_frontcamera:
32+
- - 0.029096143490519977
33+
- -0.9995463314295703
34+
- -0.007781115579835407
35+
- -0.045768971801312515
36+
- - -0.005777780139254174
37+
- 0.007616104089319731
38+
- -0.999954305063568
39+
- -0.3868171492765085
40+
- - 0.9995599190096819
41+
- 0.02913977151915098
42+
- -0.005553559684576381
43+
- -0.6975440651652165
44+
- - 0.0
45+
- 0.0
46+
- 0.0
47+
- 1.0
48+
T_toplidar_vehicle:
49+
- - 0.9995177984237671
50+
- -0.020904183387756348
51+
- 0.022959932684898376
52+
- 0.0
53+
- - 0.020975051447749138
54+
- 0.9997758865356445
55+
- -0.0028501423075795174
56+
- 0.0
57+
- - -0.0228952094912529
58+
- 0.003330353880301118
59+
- 0.9997323155403137
60+
- 0.33000001311302185
61+
- - 0.0
62+
- 0.0
63+
- 0.0
64+
- 1.0
Lines changed: 32 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,36 @@
11
from ...utils.config import load_config_recursive
2-
import os
3-
SETTINGS_FILE = os.path.join(os.path.split(__file__)[0],'current.yaml')
2+
import os,sys
3+
4+
5+
# Identify the vehicle used and load settings else default to vehicle config at current.yaml'
6+
# default currently uses GEM e4
7+
vehicle = "default"
8+
9+
for arg in sys.argv:
10+
if arg.startswith('--'):
11+
k,v = arg.split('=',1)
12+
k = k[2:]
13+
v = v.strip('"')
14+
if k == "vehicle":
15+
vehicle = v
16+
sys.argv.remove(arg)
17+
break
18+
19+
if(vehicle == 'e2'):
20+
vehicle_config = 'e2.yaml'
21+
elif(vehicle == 'e4'):
22+
vehicle_config = 'current.yaml'
23+
elif(vehicle == 'e2_gazebo'):
24+
vehicle_config = 'e2_gazebo.yaml'
25+
elif(vehicle == 'e4_gazebo'):
26+
vehicle_config = 'e4_gazebo.yaml'
27+
else:
28+
print("Unknown vehicle argument passed")
29+
vehicle = "default"
30+
vehicle_config = 'current.yaml'
31+
32+
SETTINGS_FILE = os.path.join(os.path.split(__file__)[0],vehicle_config)
433
print("**************************************************************")
5-
print("Loading default settings from",SETTINGS_FILE)
34+
print(f"Loading {vehicle} settings from",SETTINGS_FILE)
635
print("**************************************************************")
736
SETTINGS = load_config_recursive(SETTINGS_FILE)

GEMstack/knowledge/defaults/current.yaml

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,7 @@
11
# ********* Main settings entry point for behavior stack ***********
22

33
# Configure settings for the vehicle / vehicle model
4-
# vehicle: !include ../vehicle/gem_e4.yaml
5-
vehicle: !include ../vehicle/gem_e2_gazebo.yaml
4+
vehicle: !include ../vehicle/gem_e4.yaml
65

76
#arguments for algorithm components here
87
model_predictive_controller:
@@ -13,8 +12,8 @@ control:
1312
brake_amount : 0.5
1413
brake_speed : 2.0
1514
pure_pursuit:
16-
lookahead: 2.0
17-
lookahead_scale: 3.0
15+
lookahead: 4.0
16+
lookahead_scale: 1.0
1817
crosstrack_gain: 1.0
1918
desired_speed: trajectory
2019
longitudinal_control:
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
# ********* Main settings entry point for behavior stack ***********
2+
3+
# Configure settings for the vehicle / vehicle model
4+
vehicle: !include ../vehicle/gem_e2.yaml
5+
6+
#arguments for algorithm components here
7+
model_predictive_controller:
8+
dt: 0.1
9+
lookahead: 20
10+
control:
11+
recovery:
12+
brake_amount : 0.5
13+
brake_speed : 2.0
14+
pure_pursuit:
15+
lookahead: 2.0
16+
lookahead_scale: 3.0
17+
crosstrack_gain: 1.0
18+
desired_speed: trajectory
19+
longitudinal_control:
20+
pid_p: 1.0
21+
pid_i: 0.1
22+
pid_d: 0.0
23+
24+
#configure the simulator, if using
25+
simulator:
26+
dt: 0.01
27+
real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1
28+
gnss_emulator:
29+
dt: 0.1 #10Hz
30+
#position_noise: 0.1 #10cm noise
31+
#orientation_noise: 0.04 #2.3 degrees noise
32+
#velocity_noise:
33+
# constant: 0.04 #4cm/s noise
34+
# linear: 0.02 #2% noise
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
# ********* Main settings entry point for behavior stack ***********
2+
3+
# Configure settings for the vehicle / vehicle model
4+
vehicle: !include ../vehicle/gem_e2_gazebo.yaml
5+
6+
#arguments for algorithm components here
7+
model_predictive_controller:
8+
dt: 0.1
9+
lookahead: 20
10+
control:
11+
recovery:
12+
brake_amount : 0.5
13+
brake_speed : 2.0
14+
pure_pursuit:
15+
lookahead: 4.0
16+
lookahead_scale: 3.0
17+
crosstrack_gain: 1.0
18+
desired_speed: trajectory
19+
longitudinal_control:
20+
pid_p: 0.1
21+
pid_i: 0.5
22+
pid_d: 0.5
23+
24+
#configure the simulator, if using
25+
simulator:
26+
dt: 0.01
27+
real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1
28+
gnss_emulator:
29+
dt: 0.1 #10Hz
30+
#position_noise: 0.1 #10cm noise
31+
#orientation_noise: 0.04 #2.3 degrees noise
32+
#velocity_noise:
33+
# constant: 0.04 #4cm/s noise
34+
# linear: 0.02 #2% noise
Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
# ********* Main settings entry point for behavior stack ***********
2+
3+
# Configure settings for the vehicle / vehicle model
4+
vehicle: !include ../vehicle/gem_e4_gazebo.yaml
5+
6+
#arguments for algorithm components here
7+
model_predictive_controller:
8+
dt: 0.1
9+
lookahead: 20
10+
control:
11+
recovery:
12+
brake_amount : 0.5
13+
brake_speed : 2.0
14+
pure_pursuit:
15+
lookahead: 2.5
16+
lookahead_scale: 3.0
17+
crosstrack_gain: 0.5
18+
desired_speed: trajectory
19+
longitudinal_control:
20+
pid_p: 1.5
21+
pid_i: 0.2
22+
pid_d: 0.0
23+
24+
#configure the simulator, if using
25+
simulator:
26+
dt: 0.01
27+
real_time_multiplier: 1.0 # make the simulator run faster than real time by making this > 1
28+
gnss_emulator:
29+
dt: 0.1 #10Hz
30+
#position_noise: 0.1 #10cm noise
31+
#orientation_noise: 0.04 #2.3 degrees noise
32+
#velocity_noise:
33+
# constant: 0.04 #4cm/s noise
34+
# linear: 0.02 #2% noise

GEMstack/knowledge/vehicle/gem_e2_gazebo.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,5 +9,5 @@ geometry: !include gem_e2_geometry.yaml
99
dynamics: !include gem_e2_dynamics.yaml
1010
limits: !include gem_e2_slow_limits.yaml
1111
control_defaults: !include gem_e2_control_defaults.yaml
12-
calibration: !include ../calibration/gem_e2.yaml
12+
calibration: !include ../calibration/gem_e2_gazebo.yaml
1313
sensors: !include gem_e2_sensor_environment_gazebo.yaml
Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
ros_topics:
22
top_lidar: /velodyne_points
33
front_camera: /front_single_camera/image_raw
4-
front_depth: /zed2/zed_node/depth/depth_registered
5-
gnss: /gps/fix
4+
front_depth: /notopic
5+
gps: /gps/fix
6+
imu: /imu
67

0 commit comments

Comments
 (0)