Scan Real Roads¶
The simulation.src.simulation_groundtruth.src.scan.node.ScanNode
can read the
car’s position from rosbags to create a simulated road.
The node listens to the ROS topic /tf and assumes that the car is always in the middle of the right lane. This requires a well suited rosbag.
Scanning new Roads¶
Adding new roads requires multiple (easy) steps:
Start ROS:
roscore
Ensure that ROS uses time from the rosbag:
rosparam set /use_sim_time true
Start playing the rosbag with the rosbag’s clock:
rosrun rosbag play ROSBAG_NAME --clock
(You can always pause and play using the SPACE key.)
Then start the scan node to generate a .yaml file with information about the part of the road played in the rosbag:
roslaunch simulation_groundtruth scan_node.launch file_path:=PATH_TO_RESULTING_FILE
When the node is stopped, a file containing the segment of the road the car drove while the node was running, is created.
Add the scanned road section to an existing road:
from simulation.utils.road.road import Road from simulation.utils.road.sections import CustomSection road = Road() section = CustomSection.from_yaml(FILEPATH) road.append(section)
Currently, intersections can not be recorded like this. The best practice is to simply record the road before and after the intersection separately.
Example: Carolo-Cup 2020 Training Loop¶
A road that has been recreated from a rosbag is our training road at the Carolo-Cup in 2020. Some additional road sections and minor adjustments were required to fit all parts together.
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 | import math
import os
from simulation.utils.geometry import Point
from simulation.utils.road.road import Road # Definition of the road class
from simulation.utils.road.sections import (
CubicBezier,
CustomSection,
Intersection,
RightCircularArc,
StraightRoad,
)
road = Road()
custom_part_one: CustomSection = CustomSection.from_yaml(
os.path.join(os.path.dirname(__file__), "./cc20_scans/training_part1.yaml")
)
road.append(custom_part_one)
road.append(StraightRoad(length=0.1))
road.append(RightCircularArc(radius=3, angle=math.radians(17)))
road.append(StraightRoad(length=0.08))
road.append(
CubicBezier(
p1=Point(0.1, 0),
p2=Point(0.9, -0.05),
p3=Point(1.0, -0.05),
left_line_marking=StraightRoad.MISSING_LINE_MARKING,
right_line_marking=StraightRoad.MISSING_LINE_MARKING,
middle_line_marking=StraightRoad.MISSING_LINE_MARKING,
)
)
road.append(
CustomSection.from_yaml(
os.path.join(os.path.dirname(__file__), "./cc20_scans/training_loop.yaml")
)
)
road.append(StraightRoad(length=0.85))
road.append(
Intersection(size=1.1, angle=math.radians(82), exit_direction=Intersection.STRAIGHT)
)
road.append(
CustomSection.from_yaml(
os.path.join(os.path.dirname(__file__), "./cc20_scans/training_part2.yaml")
)
)
road.close_loop()
|