How to Write Tests Using the Simulation¶
This drive test utility package located in simulation.utils.drive_test
enables to
rapidly execute a lot of tests in an efficient way.
Drive tests for a number of parking scenarios.
Create your own Tests¶
You can execute the test with this command:
python -m simulation.utils.drive_test.run --config $KITCAR_REPO_PATH/kitcar-gazebo-simulation/docs/content/tutorials/resources/minimal_drive_test_config.yaml
This executes the Python package and gives it a path to a config that defines which tests should be executed.
After the test finishes, this table is displayed:
╒════════════════╤════════════════════╤══════════════╤══════════════════════════╕
│ desc │ road │ time_limit │ conclusion │
╞════════════════╪════════════════════╪══════════════╪══════════════════════════╡
│ Curvy road. │ ci_roads/curves │ 300 │ Success (Expected: None) │
├────────────────┼────────────────────┼──────────────┼──────────────────────────┤
│ Obstacle road. │ ci_roads/obstacles │ 300 │ Failure (Expected: None) │
╘════════════════╧════════════════════╧══════════════╧══════════════════════════╛
The file docs/content/tutorials/resouces/minimal_drive_test_config.yaml
which we pass to the drive_test looks like this:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 | table_header:
- desc
- road
- time_limit
- conclusion
table_column_max_width: 0
# Defaults get applied to every test
default_args:
mission_mode: 1
gui: true
time_limit: 300
tests:
- desc: Curvy road.
road: ci_roads/curves
- desc: Obstacle road.
road: ci_roads/obstacles
|
Take a closer look at this part:
1 2 3 4 5 | tests:
- desc: Curvy road.
road: ci_roads/curves
- desc: Obstacle road.
road: ci_roads/obstacles
|
The list tests defines each test that should be executed during runtime. The definiton starts with a hypen followed by a list of parameters. Take a look at the table again. Every test has it’s own row filled with these parameters.
As you may noticed, there are parameters inside the table that aren’t inside the list tests. There are default parameters which are applied to every test:
1 2 3 4 5 | # Defaults get applied to every test
default_args:
mission_mode: 1
gui: true
time_limit: 300
|
This improves readability inside the yaml file. You can overwrite a default parameter by overwriting it inside the tests list!
Modifying the table¶
First, the header. The list table_header defines the header of the ouput table.
1 2 3 4 5 | table_header:
- desc
- road
- time_limit
- conclusion
|
And this line defines the width of the table. Setting this to 0 disables this feature.
1 | table_column_max_width: 0
|
Valid parameters¶
Until now we mentioned that you can pass some paramters. But which paramters can be passed?
There are some special paramters:
desc: A description for the test. Just so you know what you are doing.
result: If the test completed successfully.
must_succeed: If you expected the test to complete successfully.
conclusion: Shortcut for result and must_succeed in one box.
Every other valid parameter can be set inside the launch file
simulation/src/simulation_evaluation/launch/test/drive.test
:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 | <?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="road" default="default_road"/>
<arg name="seed" default="KITCAR"/>
<arg name="gui" default="false"/>
<arg name="mission_mode" default="1"/>
<arg name="time_limit" default="120"/>
<arg name="sim_rate_min" default="200"/>
<arg name="sim_rate_max" default="2000"/>
<arg name="include_jetson" default="false"/>
<arg name="evaluate_sign_detection" default="false"/>
<arg name="sign_evaluation_plots_path" default="$(env KITCAR_REPO_PATH)/kitcar-gazebo-simulation/plots/"/>
<arg name="automatic_drive" default="false"/>
<arg name="path_file" default="$(find gazebo_simulation)/param/automatic_drive/path.yaml" />
<!-- Expect correct behavior (msg/Referee.msg/COMPLETED) by default.-->
<arg name="expected_result_state" default="2" />
<arg name="expected_parking_successes" default="0" />
<arg name="expect_exact_parking_successes" default="false" />
<!-- Whether a rosbag of the drive should be recorded and where it's stored. -->
<arg name="record_rosbag" default="false"/>
<arg name="rosbag_path" default="/rosbags/drive_test"/>
<include file="$(find gazebo_simulation)/launch/master.launch">
<arg name="road" value="$(arg road)"/>
<arg name="seed" value="$(arg seed)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="evaluate" value="true"/>
<arg name="control_sim_rate" value="true"/>
<arg name="force_reload_road" value="true"/>
<arg name="sim_rate_min" default="$(arg sim_rate_min)"/>
<arg name="sim_rate_max" default="$(arg sim_rate_max)"/>
<arg name="include_jetson" default="$(arg include_jetson)"/>
<arg name="evaluate_sign_detection" default="$(arg evaluate_sign_detection)"/>
<arg name="sign_evaluation_plots_path" default="$(arg sign_evaluation_plots_path)"/>
<arg if="$(arg automatic_drive)" name="include_brain" value="false" />
<arg if="$(arg automatic_drive)" name="include_vehicle_simulation" value="false" />
<arg if="$(arg automatic_drive)" name="include_mission_mode_plugin" value="false" />
</include>
<!-- Record a rosbag of the drive.
All topics are recorded, but compressed images left out as they create errors. -->
<node if="$(arg record_rosbag)" name="record" type="record.sh" pkg="kitcar_rosbag" args='-o $(arg rosbag_path) -a -x "(.*)/compressed(.*)"' />
<include if="$(arg automatic_drive)" file="$(find gazebo_simulation)/launch/automatic_drive.launch">
<arg name="path_file" value="$(arg path_file)"/>
</include>
<include if="$(arg evaluate_sign_detection)" file="$(find simulation_evaluation)/launch/sign_evaluation_node.launch">
<arg name="path" value="$(arg sign_evaluation_plots_path)"/>
</include>
<!-- The expected argument allows for generic tests. Possible values are positive, negative -->
<test launch-prefix="coverage run -p" test-name="drive_test" pkg="simulation_evaluation" time-limit="$(arg time_limit)" type="drive_test">
<param name="mission_mode" value="$(arg mission_mode)"/>
<param name="expected_result_state" value="$(arg expected_result_state)"/>
<param name="expected_parking_successes" value="$(arg expected_parking_successes)"/>
<param name="expect_exact_parking_successes" value="$(arg expect_exact_parking_successes)"/>
<rosparam file="$(find simulation_evaluation)/param/drive/topics.yaml" command="load" ns="topics" />
<rosparam file="$(find simulation_evaluation)/param/referee/topics.yaml" command="load" ns="topics/referee" />
<rosparam file="$(find simulation_evaluation)/param/state_machine/topics.yaml" command="load" ns="topics/state_machine" />
<rosparam file="$(find gazebo_simulation)/param/car_state/topics.yaml" command="load" ns="topics/car_state" />
<rosparam file="$(find simulation_groundtruth)/param/groundtruth/topics.yaml" command="load" ns="topics/groundtruth" />
<rosparam file="$(find simulation_brain_link)/param/vehicle_simulation_link/default.yaml" command="load" ns="vehicle_simulation_link" />
</test>
</launch>
|
Take a closer look at the beginning of this file. There you can see every other valid parameter that can be passed to the script. You are also able to add your own of course!
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 | <arg name="road" default="default_road"/>
<arg name="seed" default="KITCAR"/>
<arg name="gui" default="false"/>
<arg name="mission_mode" default="1"/>
<arg name="time_limit" default="120"/>
<arg name="sim_rate_min" default="200"/>
<arg name="sim_rate_max" default="2000"/>
<arg name="include_jetson" default="false"/>
<arg name="evaluate_sign_detection" default="false"/>
<arg name="sign_evaluation_plots_path" default="$(env KITCAR_REPO_PATH)/kitcar-gazebo-simulation/plots/"/>
<arg name="automatic_drive" default="false"/>
<arg name="path_file" default="$(find gazebo_simulation)/param/automatic_drive/path.yaml" />
<!-- Expect correct behavior (msg/Referee.msg/COMPLETED) by default.-->
<arg name="expected_result_state" default="2" />
<arg name="expected_parking_successes" default="0" />
<arg name="expect_exact_parking_successes" default="false" />
<!-- Whether a rosbag of the drive should be recorded and where it's stored. -->
<arg name="record_rosbag" default="false"/>
<arg name="rosbag_path" default="/rosbags/drive_test"/>
|
Tests <=> Tickets¶
Tests can also be allowed to fail. What?? Why would one write a test and then allow it to fail?
One can specify what the car should be capable of and thus define tests that continuously check what the car is currently capable of.
The idea is simple. In traditional development tickets are used to plan and organize work. At some point, it is decided what is currently good enough and what still has to be done. In that sense, the tests are the same as writing tickets.
To specify a test as allowed to fail, just add the argument must_succeed: false
:
...
tests:
- mission_mode: 1
road: example_road
must_succeed: false
...
Example
The following is a simple example to show how to test the car’s behavior at multiple
intersections closely after one another.
The road is called ci_roads/double_intersection.py
contains two intersections
that can be modified using environment variables:
"""A road with two intersections."""
import os
from simulation.utils.road.road import Road # Definition of the road class
from simulation.utils.road.sections import Intersection, StraightRoad
def direction_str_to_int(env: str) -> int:
"""Convert a turn env variable to an Intersection attribute.
This allows to specify "straight,left,right" as turn options through environment
variables.
"""
turn = os.environ.get(env, "straight")
return getattr(Intersection, turn.upper())
# Read environment variables:
first_turn = direction_str_to_int("FIRST_TURN")
second_turn = direction_str_to_int("SECOND_TURN")
"""Definition of the actual road.
Just a straight beginning and then two intersections.
"""
road = Road()
road.append(StraightRoad(length=2))
road.append(Intersection(turn=first_turn, rule=Intersection.STOP))
road.append(StraightRoad(length=1))
road.append(Intersection(turn=second_turn, rule=Intersection.YIELD))
road.append(StraightRoad(length=2))
A config that creates tests for all turn combinations looks like:
table_header:
- desc
- road
- time_limit
- conclusion
table_column_max_width: 40
# Defaults get applied to every test
default_args:
time_limit: 300
mission_mode: 2
gui: true
road: ci_roads/double_intersection
must_succeed: true
tests:
# First turn right
- desc: Right&right intersections.
environment:
FIRST_TURN: right
SECOND_TURN: right
- desc: Right&left intersections.
environment:
FIRST_TURN: right
SECOND_TURN: left
# First turn left
- desc: Left&right intersections.
environment:
FIRST_TURN: left
SECOND_TURN: right
- desc: Left&left intersections.
environment:
FIRST_TURN: left
SECOND_TURN: left
It can be executed with
python3 -m simulation.utils.drive_test.run --config $KITCAR_REPO_PATH/kitcar-gazebo-simulation/docs/content/tutorials/resources/double_intersection_drive_test_config.yaml
The tests executed by the config do not all succeed and reveal that the car slightly overshoots when turning left:

The result displayed when running the tests look are:
╒════════════════════════════╤══════════════════════════════╤══════════════╤═════════════════════════════╕
│ desc │ road │ time_limit │ conclusion │
╞════════════════════════════╪══════════════════════════════╪══════════════╪═════════════════════════════╡
│ Right&right intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: Success) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Right&left intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: Success) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Left&right intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: Success) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Left&left intersections. │ ci_roads/double_intersection │ 300 │ Failure (Expected: Success) │
╘════════════════════════════╧══════════════════════════════╧══════════════╧═════════════════════════════╛
Job has failed.
The first left turns sometimes fail (as seen above) because the car slightly drives off the road after
turning.
One can now specify the failures by adding must_succeed: false
to tests that fail.
The result then looks like:
╒════════════════════════════╤══════════════════════════════╤══════════════╤═════════════════════════════╕
│ desc │ road │ time_limit │ conclusion │
╞════════════════════════════╪══════════════════════════════╪══════════════╪═════════════════════════════╡
│ Right&right intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: Success) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Right&left intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: Success) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Left&right intersections. │ ci_roads/double_intersection │ 300 │ Success (Expected: None) │
├────────────────────────────┼──────────────────────────────┼──────────────┼─────────────────────────────┤
│ Left&left intersections. │ ci_roads/double_intersection │ 300 │ Failure (Expected: None) │
╘════════════════════════════╧══════════════════════════════╧══════════════╧═════════════════════════════╛
All roads marked with must_succeed have been run successfully.
Why? Continuous Integration!¶
New code is hard to test. The more you rapidly you develop new features, the harder it is. Sometimes certain changes in behavior are not predicted. Some bugs happen rarely. ROS tests and Gtests have been used to test individual components for a long time. These drive tests allow to test situations instead of components. They are by no means a replacement but a great addition to existing component tests!
Example
Adding the example of above to an existing Gitlab-CI is very easy. The only requirement is that the right docker image is available.
If this is the case, a job executing the above config is quite easy:
# A simple CI job that runs the config above!
test-double-intersection:
image: git.kitcar-team.de:4567/kitcar/kitcar-gazebo-simulation/kitcar_ros_ci
stage: test
script:
- python3 -m simulation.utils.drive_test.run --config $KITCAR_REPO_PATH/kitcar-gazebo-simulation/docs/content/tutorials/resources/double_intersection_drive_test_config.yaml
And just like that, it is ensured that the car can handle double intersections for right turns and one can easily adapt the config above after fixing left turns!