If you only need to generate test scenarios or analyze the record file, or if your PC cannot support the full installation of Autoware, you can opt for the Reduced Installation of Autoware instead. This reduced version includes the essential packages needed to analyze maps and deserialize record data.
As for now, we set the traffic rules using the lanelet2 built-in value (Germany). The best way is to define a custom traffic rule class and use it for routing.
tr_veh = ll2.traffic_rules.create(ll2.traffic_rules.Locations.Germany,
ll2.traffic_rules.Participants.Vehicle)
tr_ped = ll2.traffic_rules.create(ll2.traffic_rules.Locations.Germany,
ll2.traffic_rules.Participants.Pedestrian)
tr_bic = ll2.traffic_rules.create(ll2.traffic_rules.Locations.Germany,
ll2.traffic_rules.Participants.Bicycle)
map_parser = MapService.instance(ll_map=ll2_map,
projector=self.projector,
rg_veh=RoutingGraph(ll2_map, tr_veh),
rg_ped=RoutingGraph(ll2_map, tr_ped),
rg_bic=RoutingGraph(ll2_map, tr_bic),
map_name=map_name)
Define the size of the ego car in autoware/utils.py
# VEHICLE CONFIGS FOR AUTOWARE
AUTOWARE_VEHICLE_LENGTH = 4.89
AUTOWARE_VEHICLE_WIDTH = 1.64+0.128*2
AUTOWARE_VEHICLE_HEIGHT = 2.5
AUTOWARE_VEHICLE_back_edge_to_center = 1.1
When converting genetic representation to the input for other simulators (like CARLA), you should create a custom class to replace the OpenScenario
class. This custom class, which we defined, is used to convert the representation to the TIER IV Scenario Format version 2.0
def generate_scenario(
self, gen_id: int, sce_id: int, min_obs: int, max_obs: int
) -> OpenScenario:
num_obs = random.randint(min_obs, max_obs)
ego_car = self.generate_ego_car()
return OpenScenario(
generation_id=gen_id,
scenario_id=sce_id,
ego_car=ego_car,
obstacles=[self.generate_obstacle(ego_car) for _ in range(num_obs)],
map_name=self.map_service.map_name,
)
As for now, due to the nature of Scenario Simulator v2, we do not alter the sizes for each obstacle type. If you choose another simulator, you can change this code based on the simulator.
ObstacleConstraints = {
ObstacleType.CAR: {
"speed": (2.0, 14.0),
"width": (1.8, 1.8),
"length": (4.0, 4.0),
"height": (2.5, 2.5),
},
ObstacleType.BUS: {
"speed": (2.0, 14.0),
"width": (2.5, 2.5),
"length": (12.0, 12.0),
"height": (2.5, 2.5),
},
ObstacleType.TRUCK: {
"speed": (2.0, 14.0),
"width": (2.5, 2.5),
"length": (8.4, 8.4),
"height": (2.5, 2.5),
},
ObstacleType.MOTORCYCLE: {
"speed": (2.0, 14.0),
"width": (0.8, 0.8),
"length": (2.2, 2.2),
"height": (2.5, 2.5)
},
ObstacleType.BICYCLE: {
"speed": (1.6, 8.3),
"width": (0.8, 0.8),
"length": (2.0, 2.0),
"height": (2.5, 2.5),
},
ObstacleType.PEDESTRIAN: {
"speed": (1.25, 2.9),
"width": (0.8, 0.8),
"length": (0.8, 0.8),
"height": (2.0, 2.0),
},
}
Regarding the generation of the ego car, you can find an explanation in this note about why certain lines of code were added.
final_lane_id = -1
need_to_cut = True
while True:
if len(successors) == 0:
break
final_lane_id = random.choice(successors)
final_lane_cg_neighbours = self.map_service.get_changable_neighbours(final_lane_id)
if len(final_lane_cg_neighbours) != 0:
if random.random() < 0.8:
# force lane change due to limited execution time
candidate = random.choice(final_lane_cg_neighbours)
if self.map_service.get_length_of_lane(candidate) >= k_min_lane_length:
final_lane_id = candidate
# out of lanes condition
if self.map_service.get_length_of_lane(final_lane_id) - 6.0 <= 0:
if len(self.map_service.get_successors_for_lane(final_lane_id)) > 0:
need_to_cut = False
break
else:
successors.remove(final_lane_id) # remove this candidate, out of lanes
else:
if len(self.map_service.get_successors_for_lane(final_lane_id)) > 0:
need_to_cut = False # no need to cut since there is another successor lane
else:
need_to_cut = True # need to cut since there is no other successor lane
break
You can refer to autoware_record for instructions on its usage. This is an updated version of rosbag_reader.py
. Currently, we have completed unit testing of autoware_record
, but integration testing with scenoRITA is still pending. Therefore, we are using rosbag_reader.py
to read all the records for now.
The most different part is that when using rosbag_reader.py
, you should deserialize the message manually after calling read_messages()
. In src/scenoRITA/components/oracles/__init__.py
:
for topic, message, t in reader.read_messages():
if not has_localization and topic == '/localization/kinematic_state':
has_localization = True
if not has_ground_truth and topic == '/perception/object_recognition/ground_truth/objects':
has_ground_truth = True
if topic in self.topic_names():
msg = reader.deserialize_msg(message, topic) <-----------
try:
self.oracle_manager.on_new_message(topic, msg, t)
except OracleInterrupt:
break
However, when using the updated autoware/autoware_record/record.py
, please refer to Speed Up Read for instruction to use. In this case, you do not need to manually call deserialize_msg()
anymore.
For now, we modified the source code like this:
However, here is one potential issue: We only record the necessary topics for record analysis (many planning topics are not recorded)
To resolve this, we may have two solutions:
- Identify more planning topics and modify the source code accordingly
- Modify the source code to compress the ROS bag file (Additional notes: the compressed ROS bag file should be de-compressed and then analyzed)
Currently, the reduced installation of Autoware is compatible with the Autoware Universe v1.0 branch. However, you might encounter issues if you pair the reduced installation with the Autoware Universe main branch, as Autoware developers are actively evolving the custom ROS messages and services.
We do not configure traffic lights in the scenario description file. If you want to use traffic light features, there is one file you need to modify before Installation Step 11: run_scenario.sh.
You should modify it according to this post:
Changing this line of code
to
architecture_type:=awf/universe/20230906