6.4. Test the pipeline for driving a mission¶
6.4.1. Prerequisites¶
6.4.1.1. Rosbag¶
Download (see How the drive is structured for data from and for test days) and prepare (migrate, see Migrating Rosbags for pipeline testing purposes) a rosbag containing the recording of a driven trackdrive. Place the rosbag in the rosbags directory (
as_ros/rosbags
)Trackdrive and Autocross: We currently recommend rosbags recorded with Eva in May ‘22 (e.g. Run 370), see for migration here: Data recorded with Eva in May ‘22
Skidpad: We currently recommend rosbags recorded with Eva in May ‘22 (e.g. Run 377), see for migration here: Data recorded with Eva in May ‘22
EBS Test and Acceleration: We currently recommend rosbags recorded with Emma in KW 40 ‘22 (e.g. Run 592), see for migration here: Data recorded with Emma in KW 44 ‘22
6.4.1.2. Configuration¶
The autonomous system has a lot of parameters that can be changed and tuned. The next section will provide a small overview which parameters should be checked anyways.
Some paramaters regarding the dynamics of the vehicle have to be adapted according to meausrements inside the rosbag since e.g. the model predict control is going crazy if the drives faster than the trajectory is planned.
Check the
src/utilities/config/test_track.yaml
config, especiallySet the
test_day
to<test_day_name>_sim
Set the
track_layout
according to the current mission. You might use the same layout for Trackdrive and Autocross since they might use the same track layout.
Check the
src/camera_perception/config/perception.yaml
, especiallySet
camera_usage_strategy
according to how you want to use the different cameras.Set
detection_image
to whether a detection image should be created or not. Keep in mind you can create a detection image by using the rosbag migrator in post processing: Creating Visualization for recorded Rosbags
Check the
src/slam/config/slam.yaml
, especiallyThe most important parameters and their meaning are described in the doc string of
slam
Set
preloading/activated
according to whether you want to preload a manual created map or previously tracked map to preload into slamSet
preloading/align
according to whether you want to align the preloaded mapSet
<sensor_name>/active
according to whether you want to and can use this sensor, e.g. maybe one wheelspeed sensor was defect.
Check the
src/path_planning/config/path_planning.yaml
, especiallySet
track_width_min
according to you measured minimum track width
Check the
src/motion_planning/config/local_motion_planning.yaml
, especiallySet
velocity_profile/a_x_factor
according to which measurements you can observe inside the rosbag.Set
velocity_profile/a_y_factor
according to which measurements you can observe inside the rosbag.Set
velocity_profile/v_max
according to which measurements you can observe inside the rosbag.Set
velocity_profile/a_x_factor_completed
according to which measurements you can observe inside the rosbag.
Check the
src/motion_planning/config/global_motion_planning.yaml
, especiallySet
velocity_profile/a_x_factor
according to which measurements you can observe inside the rosbag.Set
velocity_profile/a_y_factor
according to which measurements you can observe inside the rosbag.Set
velocity_profile/v_max
according to which measurements you can observe inside the rosbag.Set
velocity_profile/a_x_factor_completed
according to which measurements you can observe inside the rosbag.
6.4.1.3. Map Generation¶
If you want to use preloading you might need to generate a manual map first. You there are 3 utilities you can use
6.4.2. Running the pipeline¶
6.4.2.1. General Approach¶
There exists a custom launch file to debug the complete pipeline (debug_pipeline.launch
in utilities
ros package). Among others, you can specify to not run specific ROS modules. See below.
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/<rosbag_name>.bag mission:=<mission_id> vehicle:=<vehicle_name>
Mission ID |
Mission Name |
---|---|
0 |
Manual Driving |
1 |
Acceleration |
2 |
Skidpad |
3 |
Trackdrive |
4 |
Braketest / EBS Test |
5 |
Inspection |
6 |
Autocross |
Vehicle |
Vehicle Name (ROS Launch Parameter) |
---|---|
CM-21x |
eva |
CM-22x |
emma |
You may want to adapt the command according to your needs:
If you use a rosbag with compressed images, you must append
republish:=yes
.If you do not need or want to execute a specific as ros module, you can exclude the module by appending the following:
<module_name>:=no
, e.g.control:=no
. Possible values:perception
,mapping
,slam
,path_planning
,motion_planning
,control
.If you want to profile the AS ROS modules, you can apppend:
profiling:=yes
.If you need to use an older camera matrix, you can specify the matrices subdirectory by appending:
matrices_subdirectory:=<matrices_subdirectory>
. Parameter value does not need a/
at the beginning or end of the path part.If you want to log the cpu usage of the various ros nodes, you can append
cpu_monitor:=yes
.If you want slam to send additional debug informations like the current predicted and actual measurements, you can append
send_debug_informations:=yes
.If your rosbag already includes tf transforms, you can append
transforms:=no
(NOT RECOMMENDED).If you want to use the camera perception, but your input rosbag does not contain uncompressed images, you need to uncompress by either
using the migrator, see Migrating Rosbags
or by appending
republish:=yes
Vehicle |
Time Frame |
Runs |
Camera matrices subdirectory |
Comment |
---|---|---|---|---|
Eva |
May 2022 |
368-388 |
eva_may |
All runs |
Emma |
KW40 (08. Oct 22) |
506-520 |
emma_kw40_accel |
Acceleration Runs |
Emma |
KW40 (08. Oct 22) |
527-533 |
emma_kw40_skidpad |
Skidpad Runs |
Emma |
KW44 (05. - 06. Nov 22) |
584-611 |
emma_kw44_accel |
Acceleration Runs |
Emma |
KW44 (05. - 06. Nov 22) |
612-614 |
emma_kw44_skidpad |
Skidpad Runs |
Emma |
KW05 (05. - 05. Feb 23) |
621-629 |
emma_kw05 |
Acceleration/Skidpad Runs |
Rennate |
KW30 (27. Jul 23) |
692-700 |
rennate_july |
Brake Test |
Rennate |
KW43 (23. Oct 23) |
n/a |
validation_day |
Camera Validation Day |
Rennate |
Mar - Apr 24 |
n/a |
sensorfusion_720/_2k |
Sensorfusion Testing |
6.4.2.2. Current Recommendations¶
There exists recommendations for the simulating different disciplines. You need to download (see How the drive is structured for data from and for test days) and migrate (see Migrating Rosbags) the rosbags first.
6.4.2.2.1. Acceleration¶
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/testing/run_592_m.bag mission:=1 vehicle:=emma matrices_subdirectory:=emma_kw44 cpu_monitor:=yes send_debug_informations:=yes
6.4.2.2.2. EBS Test¶
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/testing/run_592_m.bag mission:=4 vehicle:=emma matrices_subdirectory:=emma_kw44 cpu_monitor:=yes send_debug_informations:=yes
6.4.2.2.3. Skidpad¶
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/testing/run_377_m.bag mission:=2 vehicle:=eva matrices_subdirectory:=eva_may cpu_monitor:=yes send_debug_informations:=yes
6.4.2.2.4. Autocross¶
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/testing/run_370_m.bag mission:=6 vehicle:=eva matrices_subdirectory:=eva_may cpu_monitor:=yes send_debug_informations:=yes
6.4.2.2.5. Trackdrive¶
roslaunch utilities debug_pipeline.launch input_rosbag:=/workspace/as_ros/rosbags/testing/run_370_m.bag mission:=3 vehicle:=eva matrices_subdirectory:=eva_may cpu_monitor:=yes send_debug_informations:=yes