Copy disabled (too large)
Download .txt
Showing preview only (25,432K chars total). Download the full file to get everything.
Repository: OpenDriveLab/ThinkTwice
Branch: main
Commit: e9cf2fc078f6
Files: 392
Total size: 24.2 MB
Directory structure:
gitextract_y09f2xlv/
├── .github/
│ └── FUNDING.yml
├── .gitignore
├── LICENSE
├── README.md
├── agents/
│ ├── __init__.py
│ ├── navigation/
│ │ ├── __init__.py
│ │ ├── agent.py
│ │ ├── basic_agent.py
│ │ ├── behavior_agent.py
│ │ ├── controller.py
│ │ ├── global_route_planner.py
│ │ ├── global_route_planner_dao.py
│ │ ├── local_planner.py
│ │ ├── local_planner_behavior.py
│ │ ├── roaming_agent.py
│ │ └── types_behavior.py
│ └── tools/
│ ├── __init__.py
│ └── misc.py
├── camera_calibration/
│ ├── README.md
│ ├── calculate_distortion_parameters.py
│ ├── collect_data_for_calibration.py
│ └── undistort.py
├── dataset/
│ └── tools/
│ ├── generate_metadata.py
│ └── generate_random_routes.py
├── docs/
│ ├── DATA_PREP.md
│ ├── EVAL.md
│ ├── INSTALL.md
│ └── TRAIN.md
├── leaderboard/
│ ├── LICENSE
│ ├── README.md
│ ├── data/
│ │ ├── routes_for_evaluation/
│ │ │ ├── routes_longest6.xml
│ │ │ └── routes_town05_long.xml
│ │ ├── routes_for_open_loop_training/
│ │ │ ├── routes_town01_00.xml
│ │ │ ├── routes_town01_01.xml
│ │ │ ├── routes_town01_02.xml
│ │ │ ├── routes_town01_03.xml
│ │ │ ├── routes_town01_04.xml
│ │ │ ├── routes_town01_05.xml
│ │ │ ├── routes_town01_06.xml
│ │ │ ├── routes_town01_07.xml
│ │ │ ├── routes_town01_08.xml
│ │ │ ├── routes_town01_09.xml
│ │ │ ├── routes_town01_10.xml
│ │ │ ├── routes_town01_11.xml
│ │ │ ├── routes_town01_val.xml
│ │ │ ├── routes_town02_00.xml
│ │ │ ├── routes_town02_01.xml
│ │ │ ├── routes_town02_02.xml
│ │ │ ├── routes_town02_03.xml
│ │ │ ├── routes_town02_04.xml
│ │ │ ├── routes_town02_05.xml
│ │ │ ├── routes_town02_06.xml
│ │ │ ├── routes_town02_07.xml
│ │ │ ├── routes_town02_08.xml
│ │ │ ├── routes_town02_09.xml
│ │ │ ├── routes_town02_10.xml
│ │ │ ├── routes_town02_11.xml
│ │ │ ├── routes_town02_val.xml
│ │ │ ├── routes_town03_00.xml
│ │ │ ├── routes_town03_01.xml
│ │ │ ├── routes_town03_02.xml
│ │ │ ├── routes_town03_03.xml
│ │ │ ├── routes_town03_04.xml
│ │ │ ├── routes_town03_05.xml
│ │ │ ├── routes_town03_06.xml
│ │ │ ├── routes_town03_07.xml
│ │ │ ├── routes_town03_08.xml
│ │ │ ├── routes_town03_09.xml
│ │ │ ├── routes_town03_10.xml
│ │ │ ├── routes_town03_11.xml
│ │ │ ├── routes_town03_val.xml
│ │ │ ├── routes_town04_00.xml
│ │ │ ├── routes_town04_01.xml
│ │ │ ├── routes_town04_02.xml
│ │ │ ├── routes_town04_03.xml
│ │ │ ├── routes_town04_04.xml
│ │ │ ├── routes_town04_05.xml
│ │ │ ├── routes_town04_06.xml
│ │ │ ├── routes_town04_07.xml
│ │ │ ├── routes_town04_08.xml
│ │ │ ├── routes_town04_09.xml
│ │ │ ├── routes_town04_10.xml
│ │ │ ├── routes_town04_11.xml
│ │ │ ├── routes_town04_val.xml
│ │ │ ├── routes_town05_00.xml
│ │ │ ├── routes_town05_01.xml
│ │ │ ├── routes_town05_02.xml
│ │ │ ├── routes_town05_03.xml
│ │ │ ├── routes_town05_04.xml
│ │ │ ├── routes_town05_05.xml
│ │ │ ├── routes_town05_06.xml
│ │ │ ├── routes_town05_07.xml
│ │ │ ├── routes_town05_08.xml
│ │ │ ├── routes_town05_09.xml
│ │ │ ├── routes_town05_10.xml
│ │ │ ├── routes_town05_11.xml
│ │ │ ├── routes_town05_val.xml
│ │ │ ├── routes_town06_00.xml
│ │ │ ├── routes_town06_01.xml
│ │ │ ├── routes_town06_02.xml
│ │ │ ├── routes_town06_03.xml
│ │ │ ├── routes_town06_04.xml
│ │ │ ├── routes_town06_05.xml
│ │ │ ├── routes_town06_06.xml
│ │ │ ├── routes_town06_07.xml
│ │ │ ├── routes_town06_08.xml
│ │ │ ├── routes_town06_09.xml
│ │ │ ├── routes_town06_10.xml
│ │ │ ├── routes_town06_11.xml
│ │ │ ├── routes_town06_val.xml
│ │ │ ├── routes_town07_00.xml
│ │ │ ├── routes_town07_01.xml
│ │ │ ├── routes_town07_02.xml
│ │ │ ├── routes_town07_03.xml
│ │ │ ├── routes_town07_04.xml
│ │ │ ├── routes_town07_05.xml
│ │ │ ├── routes_town07_06.xml
│ │ │ ├── routes_town07_07.xml
│ │ │ ├── routes_town07_08.xml
│ │ │ ├── routes_town07_09.xml
│ │ │ ├── routes_town07_10.xml
│ │ │ ├── routes_town07_11.xml
│ │ │ ├── routes_town07_val.xml
│ │ │ ├── routes_town10_00.xml
│ │ │ ├── routes_town10_01.xml
│ │ │ ├── routes_town10_02.xml
│ │ │ ├── routes_town10_03.xml
│ │ │ ├── routes_town10_04.xml
│ │ │ ├── routes_town10_05.xml
│ │ │ ├── routes_town10_06.xml
│ │ │ ├── routes_town10_07.xml
│ │ │ ├── routes_town10_08.xml
│ │ │ ├── routes_town10_09.xml
│ │ │ ├── routes_town10_10.xml
│ │ │ ├── routes_town10_11.xml
│ │ │ └── routes_town10_val.xml
│ │ └── scenarios/
│ │ ├── all_towns_traffic_scenarios_no256.json
│ │ └── longest6_eval_scenarios.json
│ ├── leaderboard/
│ │ ├── __init__.py
│ │ ├── autoagents/
│ │ │ ├── __init__.py
│ │ │ ├── agent_wrapper.py
│ │ │ ├── autonomous_agent.py
│ │ │ ├── dummy_agent.py
│ │ │ ├── human_agent.py
│ │ │ ├── human_agent_config.txt
│ │ │ ├── npc_agent.py
│ │ │ └── ros_agent.py
│ │ ├── envs/
│ │ │ ├── __init__.py
│ │ │ └── sensor_interface.py
│ │ ├── leaderboard_evaluator.py
│ │ ├── scenarios/
│ │ │ ├── __init__.py
│ │ │ ├── background_activity.py
│ │ │ ├── master_scenario.py
│ │ │ ├── route_scenario.py
│ │ │ ├── scenario_manager.py
│ │ │ └── scenarioatomics/
│ │ │ ├── __init__.py
│ │ │ └── atomic_criteria.py
│ │ └── utils/
│ │ ├── __init__.py
│ │ ├── checkpoint_tools.py
│ │ ├── result_writer.py
│ │ ├── route_indexer.py
│ │ ├── route_manipulation.py
│ │ ├── route_parser.py
│ │ └── statistics_manager.py
│ ├── scripts/
│ │ ├── collect_data.sh
│ │ ├── evaluation_longest6.sh
│ │ └── evaluation_town05long.sh
│ └── team_code/
│ ├── auto_pilot.py
│ ├── base_agent.py
│ ├── map_agent.py
│ ├── pid_controller.py
│ ├── planner.py
│ ├── roach_ap_agent_data_collection.py
│ ├── thinktwice_agent.py
│ └── thinktwice_agent_old.py
├── open_loop_training/
│ ├── __init__.py
│ ├── code/
│ │ ├── __init__.py
│ │ ├── apis/
│ │ │ ├── __init__.py
│ │ │ ├── mmdet_train.py
│ │ │ └── train.py
│ │ ├── core/
│ │ │ └── evaluation/
│ │ │ ├── __init__.py
│ │ │ ├── epoch_hook.py
│ │ │ ├── eval_hooks.py
│ │ │ └── eval_tool.py
│ │ ├── datasets/
│ │ │ ├── __init__.py
│ │ │ ├── base_dataset.py
│ │ │ ├── builder.py
│ │ │ ├── carla_dataset.py
│ │ │ ├── pipelines/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── formating.py
│ │ │ │ ├── loading.py
│ │ │ │ └── transform.py
│ │ │ └── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── distributed_sampler.py
│ │ │ ├── group_sampler.py
│ │ │ └── sampler.py
│ │ ├── encoder_decoder_framework.py
│ │ ├── model_code/
│ │ │ ├── backbones/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── lidarnet.py
│ │ │ │ └── lss.py
│ │ │ └── dense_heads/
│ │ │ ├── __init__.py
│ │ │ ├── multi_scale_deformable_attn_function.py
│ │ │ ├── thinktwice_decoder.py
│ │ │ └── utils.py
│ │ └── utils.py
│ ├── configs/
│ │ ├── _base_/
│ │ │ ├── default_runtime.py
│ │ │ └── schedules/
│ │ │ ├── cosine.py
│ │ │ ├── cyclic_20e.py
│ │ │ ├── cyclic_40e.py
│ │ │ ├── mmdet_schedule_1x.py
│ │ │ ├── schedule_2x.py
│ │ │ ├── schedule_3x.py
│ │ │ ├── seg_cosine_150e.py
│ │ │ ├── seg_cosine_200e.py
│ │ │ └── seg_cosine_50e.py
│ │ └── thinktwice.py
│ ├── ops/
│ │ └── voxel_pooling/
│ │ ├── __init__.py
│ │ ├── src/
│ │ │ ├── voxel_pooling_forward.cpp
│ │ │ └── voxel_pooling_forward_cuda.cu
│ │ └── voxel_pooling.py
│ ├── setup.py
│ └── train.py
├── roach/
│ ├── config/
│ │ └── config_agent.yaml
│ ├── criteria/
│ │ ├── blocked.py
│ │ ├── collision.py
│ │ ├── encounter_light.py
│ │ ├── outside_route_lane.py
│ │ ├── route_deviation.py
│ │ ├── run_red_light.py
│ │ └── run_stop_sign.py
│ ├── log/
│ │ └── ckpt_11833344.pth
│ ├── models/
│ │ ├── distributions.py
│ │ ├── ppo.py
│ │ ├── ppo_buffer.py
│ │ ├── ppo_policy.py
│ │ ├── torch_layers.py
│ │ └── torch_util.py
│ ├── obs_manager/
│ │ ├── actor_state/
│ │ │ ├── control.py
│ │ │ ├── route.py
│ │ │ ├── speed.py
│ │ │ └── velocity.py
│ │ └── birdview/
│ │ ├── chauffeurnet.py
│ │ ├── hdmap_generate.py
│ │ └── maps/
│ │ ├── Town01.h5
│ │ ├── Town02.h5
│ │ ├── Town03.h5
│ │ ├── Town04.h5
│ │ ├── Town05.h5
│ │ ├── Town06.h5
│ │ ├── Town07.h5
│ │ └── Town10HD.h5
│ ├── rl_birdview_agent.py
│ └── utils/
│ ├── config_utils.py
│ ├── expert_noiser.py
│ ├── rl_birdview_wrapper.py
│ ├── traffic_light.py
│ ├── transforms.py
│ └── wandb_callback.py
└── scenario_runner/
├── CARLA_VER
├── Dockerfile
├── Docs/
│ ├── CHANGELOG.md
│ ├── CODE_OF_CONDUCT.md
│ ├── CONTRIBUTING.md
│ ├── FAQ.md
│ ├── agent_evaluation.md
│ ├── coding_standard.md
│ ├── creating_new_scenario.md
│ ├── extra.css
│ ├── getting_scenariorunner.md
│ ├── getting_started.md
│ ├── index.md
│ ├── list_of_scenarios.md
│ ├── metrics_module.md
│ ├── openscenario_support.md
│ ├── requirements.txt
│ └── ros_agent.md
├── Jenkinsfile
├── LICENSE
├── README.md
├── manual_control.py
├── metrics_manager.py
├── mkdocs.yml
├── no_rendering_mode.py
├── requirements.txt
├── scenario_runner.py
└── srunner/
├── __init__.py
├── autoagents/
│ ├── __init__.py
│ ├── agent_wrapper.py
│ ├── autonomous_agent.py
│ ├── dummy_agent.py
│ ├── human_agent.py
│ ├── npc_agent.py
│ ├── ros_agent.py
│ └── sensor_interface.py
├── data/
│ ├── all_towns_traffic_scenarios1_3_4.json
│ ├── all_towns_traffic_scenarios1_3_4_8.json
│ ├── no_scenarios.json
│ ├── routes_debug.xml
│ ├── routes_devtest.xml
│ └── routes_training.xml
├── examples/
│ ├── CatalogExample.xosc
│ ├── ChangeLane.xml
│ ├── ChangingWeather.xosc
│ ├── ControlLoss.xml
│ ├── CutIn.xml
│ ├── CyclistCrossing.xosc
│ ├── FollowLeadingVehicle.xml
│ ├── FollowLeadingVehicle.xosc
│ ├── FreeRide.xml
│ ├── LaneChangeSimple.xosc
│ ├── LeadingVehicle.xml
│ ├── NoSignalJunction.xml
│ ├── ObjectCrossing.xml
│ ├── OppositeDirection.xml
│ ├── OscControllerExample.xosc
│ ├── PedestrianCrossingFront.xosc
│ ├── RunningRedLight.xml
│ ├── SignalizedJunctionLeftTurn.xml
│ ├── SignalizedJunctionRightTurn.xml
│ ├── VehicleTurning.xml
│ └── catalogs/
│ ├── ControllerCatalog.xosc
│ ├── EnvironmentCatalog.xosc
│ ├── ManeuverCatalog.xosc
│ ├── MiscObjectCatalog.xosc
│ ├── PedestrianCatalog.xosc
│ └── VehicleCatalog.xosc
├── metrics/
│ ├── data/
│ │ ├── CriteriaFilter_criteria.json
│ │ ├── DistanceBetweenVehicles_criteria.json
│ │ └── DistanceToLaneCenter_criteria.json
│ ├── examples/
│ │ ├── basic_metric.py
│ │ ├── criteria_filter.py
│ │ ├── distance_between_vehicles.py
│ │ └── distance_to_lane_center.py
│ └── tools/
│ ├── metrics_log.py
│ └── metrics_parser.py
├── openscenario/
│ ├── 0.9.x/
│ │ ├── OpenSCENARIO_Catalog.xsd
│ │ ├── OpenSCENARIO_TypeDefs.xsd
│ │ ├── OpenSCENARIO_v0.9.1.xsd
│ │ └── migration0_9_1to1_0.xslt
│ └── OpenSCENARIO.xsd
├── scenarioconfigs/
│ ├── __init__.py
│ ├── openscenario_configuration.py
│ ├── route_scenario_configuration.py
│ └── scenario_configuration.py
├── scenariomanager/
│ ├── __init__.py
│ ├── actorcontrols/
│ │ ├── __init__.py
│ │ ├── actor_control.py
│ │ ├── basic_control.py
│ │ ├── external_control.py
│ │ ├── npc_vehicle_control.py
│ │ ├── pedestrian_control.py
│ │ ├── simple_vehicle_control.py
│ │ └── vehicle_longitudinal_control.py
│ ├── carla_data_provider.py
│ ├── result_writer.py
│ ├── scenario_manager.py
│ ├── scenarioatomics/
│ │ ├── __init__.py
│ │ ├── atomic_behaviors.py
│ │ ├── atomic_criteria.py
│ │ └── atomic_trigger_conditions.py
│ ├── timer.py
│ ├── traffic_events.py
│ ├── watchdog.py
│ └── weather_sim.py
├── scenarios/
│ ├── __init__.py
│ ├── background_activity.py
│ ├── basic_scenario.py
│ ├── change_lane.py
│ ├── control_loss.py
│ ├── cut_in.py
│ ├── follow_leading_vehicle.py
│ ├── freeride.py
│ ├── junction_crossing_route.py
│ ├── maneuver_opposite_direction.py
│ ├── master_scenario.py
│ ├── no_signal_junction_crossing.py
│ ├── object_crash_intersection.py
│ ├── object_crash_vehicle.py
│ ├── open_scenario.py
│ ├── opposite_vehicle_taking_priority.py
│ ├── other_leading_vehicle.py
│ ├── route_scenario.py
│ ├── signalized_junction_left_turn.py
│ └── signalized_junction_right_turn.py
├── tools/
│ ├── __init__.py
│ ├── openscenario_parser.py
│ ├── py_trees_port.py
│ ├── route_manipulation.py
│ ├── route_parser.py
│ ├── scenario_helper.py
│ └── scenario_parser.py
└── utilities/
└── code_check_and_formatting.sh
================================================
FILE CONTENTS
================================================
================================================
FILE: .github/FUNDING.yml
================================================
# These are supported funding model platforms
github: [OpenDriveLab] # Replace with up to 4 GitHub Sponsors-enabled usernames e.g., [user1, user2]
patreon: # Replace with a single Patreon username
open_collective: # Replace with a single Open Collective username
ko_fi: # Replace with a single Ko-fi username
tidelift: # Replace with a single Tidelift platform-name/package-name e.g., npm/babel
community_bridge: # Replace with a single Community Bridge project-name e.g., cloud-foundry
liberapay: # Replace with a single Liberapay username
issuehunt: # Replace with a single IssueHunt username
otechie: # Replace with a single Otechie username
lfx_crowdfunding: # Replace with a single LFX Crowdfunding project-name e.g., cloud-foundry
custom: # Replace with up to 4 custom sponsorship URLs e.g., ['link1', 'link2']
================================================
FILE: .gitignore
================================================
*.log
*results.json
*results*.json
*.pyc
*.out
nohup.out
*.out
events*
*hparams.yaml
ckpt/
*checkpoints*
__pycache__
*work_dirs*
*batchscript*
build
*egg-info*
*cpython*
collect_data_json/*.json
dataset/town??_??
*dataset_metadata.pkl*
closed_loop_eval_log/eval_log/*
*old_version*
================================================
FILE: LICENSE
================================================
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "[]"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright [yyyy] [name of copyright owner]
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
================================================
FILE: README.md
================================================
> [!IMPORTANT]
> 🌟 Stay up to date at [opendrivelab.com](https://opendrivelab.com/#news)!
# Think Twice before Driving: Towards Scalable Decoders for End-to-End Autonomous Driving
- A SOTA Decoder for End-to-End Autonomous Driving under BEV
- [arXiv Paper](https://arxiv.org/abs/2305.06242) (CVPR 2023)

## Demo Video
[](https://youtu.be/ZhSH63O4Hsg)
## Getting Started
- [Installation](docs/INSTALL.md)
- [Closed-Loop Evaluation in Carla](docs/EVAL.md)
- [Prepare Dataset](docs/DATA_PREP.md)
- [Train Your Own Model](docs/TRAIN.md)
- [Calibrations for Different Camera Settings](camera_calibration/README.md) (Optional)
## Quick Run in Carla
Install the environment as in [Installation](docs/INSTALL.md), download our checkpoint ([GoogleDrive](https://drive.google.com/file/d/1Y2bWf8qVwqVQxqM2GOKTiR9kE9nGtkYV/view?usp=share_link) or [BaiduYun](https://pan.baidu.com/s/1OamwKOUpqK0EOqWa1Luv_g)(提取码 m5di).) (189K frames training set), put it into **open_loop_training/ckpt**, and run:
```shell
## In the ThinkTwice/ directory
CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_town05long.sh 22023 22033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py all_towns_traffic_scenarios_no256 thinktwice_town05long 2>&1 > thinktwice_town05long.log &
```
Check [closed_loop_eval_log/eval_log](closed_loop_eval_log/eval_log) to see how our model drives in Carla! :oncoming_automobile:
(In case you have a screen to see the interface of Carla simulator, you could remove *DISPLAY=* in [leaderboard/leaderboard/leaderboard_evaluator.py](leaderboard/leaderboard/leaderboard_evaluator.py) and then you could directly watch with Carla.)
## Code Structure
We give the structure of our code. Note that we only introduce those folders/files are commonly used and modified.
ThinkTwice/
├── agents # From Carla official
├── camera_calibration # When you want to use cameras with different FOV
├── closed_loop_eval_log # Save eval logs
├── collect_data_json # Save data collection logs
├── dataset # Data and metadata for training
├── leaderboard # Code for Closed-Loop Evaluation
│ ├── data # Save routes and scenarios
│ ├── scripts # Run with Carla
│ ├── team_code # Your
| | ├── roach_ap_agent_data_collection.py # Data collection
│ | └── thinktwice_agent.py # Interface for closed-loop evaluation of our model
│ ├── leaderboard # From Carla official
| | └── leaderboard_evaluator.py # Entrance of closed-loop evaluation
├── roach # Roach for data collection
├── scenario_runner # From Carla official
├── open_loop_training # Training and Neural Network
| ├── ckpt # Checkpoints
| ├── work_dirs # Training Log
| ├── code # Preprocessing, DataLoader, Model
| │ ├── apis # Training pipeline for mmdet3D
| │ ├── core # The hooks for mmdet3D
| │ ├── datasets # Preprocessing and DataLoader
| | | ├── pipelines # Functions of Preprocessing and DataLoader
| │ | ├── samplers # For DDP
| │ | └── carla_dataset.py # Framework of Preprocessing and DataLoading
| │ ├── model_code # Neural Network
| | | ├── backbones # Module of Encoder
| | | └── dense_heads # Module of Decoder and Loss Functions
| │ └── encoder_decoder_framework.py # Entrance of Neural Network
| └── train.py # Entrance of Training
## License
All assets and code are under the [Apache 2.0 license](./LICENSE) unless specified otherwise.
## Bibtex
If this work is helpful for your research, please consider citing the following BibTeX entry.
```
@inproceedings{jia2023thinktwice,
title={Think Twice before Driving: Towards Scalable Decoders for End-to-End Autonomous Driving},
author={Jia, Xiaosong and Wu, Penghao and Chen, Li and Xie, Jiangwei and He, Conghui and Yan, Junchi and Li, Hongyang},
booktitle={CVPR},
year={2023}
}
```
## Related Resources
Many thanks to the open-source community!
[](https://awesome.re)
- [End-to-end Autonomous Driving Survey](https://github.com/OpenDriveLab/End-to-end-Autonomous-Driving) (:rocket:Ours!)
- [TCP](https://github.com/OpenPerceptionX/TCP) (:rocket:Ours!)
- [BEVFormer](https://github.com/fundamentalvision/BEVFormer) (:rocket:Ours!)
- [UniAD](https://github.com/OpenDriveLab/UniAD) (:rocket:Ours!)
- [ST-P3](https://github.com/OpenPerceptionX/ST-P3) (:rocket:Ours!)
- [Carla](https://github.com/carla-simulator/carla)
- [Roach](https://github.com/zhejz/carla-roach)
- [Transfuser](https://github.com/autonomousvision/transfuser)
- [CARLA_GARGE](https://github.com/autonomousvision/carla_garage)
- [LAV](https://github.com/dotchen/LAV)
- [IBISCape](https://github.com/AbanobSoliman/IBISCape)
================================================
FILE: agents/__init__.py
================================================
================================================
FILE: agents/navigation/__init__.py
================================================
================================================
FILE: agents/navigation/agent.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module implements an agent that roams around a track following random
waypoints and avoiding other vehicles.
The agent also responds to traffic lights. """
import sys
import math
from enum import Enum
import carla
from agents.tools.misc import is_within_distance_ahead, is_within_distance, compute_distance
class AgentState(Enum):
"""
AGENT_STATE represents the possible states of a roaming agent
"""
NAVIGATING = 1
BLOCKED_BY_VEHICLE = 2
BLOCKED_RED_LIGHT = 3
class Agent(object):
"""Base class to define agents in CARLA"""
def __init__(self, vehicle):
"""
Constructor method.
:param vehicle: actor to apply to local planner logic onto
"""
self._vehicle = vehicle
self._proximity_tlight_threshold = 5.0 # meters
self._proximity_vehicle_threshold = 10.0 # meters
self._local_planner = None
self._world = self._vehicle.get_world()
try:
self._map = self._world.get_map()
except RuntimeError as error:
print('RuntimeError: {}'.format(error))
print(' The server could not send the OpenDRIVE (.xodr) file:')
print(' Make sure it exists, has the same name of your town, and is correct.')
sys.exit(1)
self._last_traffic_light = None
def get_local_planner(self):
"""Get method for protected member local planner"""
return self._local_planner
@staticmethod
def run_step(debug=False):
"""
Execute one step of navigation.
:param debug: boolean flag for debugging
:return: control
"""
control = carla.VehicleControl()
if debug:
control.steer = 0.0
control.throttle = 0.0
control.brake = 0.0
control.hand_brake = False
control.manual_gear_shift = False
return control
def _is_light_red(self, lights_list):
"""
Method to check if there is a red light affecting us. This version of
the method is compatible with both European and US style traffic lights.
:param lights_list: list containing TrafficLight objects
:return: a tuple given by (bool_flag, traffic_light), where
- bool_flag is True if there is a traffic light in RED
affecting us and False otherwise
- traffic_light is the object itself or None if there is no
red traffic light affecting us
"""
ego_vehicle_location = self._vehicle.get_location()
ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location)
for traffic_light in lights_list:
object_location = self._get_trafficlight_trigger_location(traffic_light)
object_waypoint = self._map.get_waypoint(object_location)
if object_waypoint.road_id != ego_vehicle_waypoint.road_id:
continue
ve_dir = ego_vehicle_waypoint.transform.get_forward_vector()
wp_dir = object_waypoint.transform.get_forward_vector()
dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z
if dot_ve_wp < 0:
continue
if is_within_distance_ahead(object_waypoint.transform,
self._vehicle.get_transform(),
self._proximity_tlight_threshold):
if traffic_light.state == carla.TrafficLightState.Red:
return (True, traffic_light)
return (False, None)
def _get_trafficlight_trigger_location(self, traffic_light): # pylint: disable=no-self-use
"""
Calculates the yaw of the waypoint that represents the trigger volume of the traffic light
"""
def rotate_point(point, radians):
"""
rotate a given point by a given angle
"""
rotated_x = math.cos(radians) * point.x - math.sin(radians) * point.y
rotated_y = math.sin(radians) * point.x - math.cos(radians) * point.y
return carla.Vector3D(rotated_x, rotated_y, point.z)
base_transform = traffic_light.get_transform()
base_rot = base_transform.rotation.yaw
area_loc = base_transform.transform(traffic_light.trigger_volume.location)
area_ext = traffic_light.trigger_volume.extent
point = rotate_point(carla.Vector3D(0, 0, area_ext.z), math.radians(base_rot))
point_location = area_loc + carla.Location(x=point.x, y=point.y)
return carla.Location(point_location.x, point_location.y, point_location.z)
def _bh_is_vehicle_hazard(self, ego_wpt, ego_loc, vehicle_list,
proximity_th, up_angle_th, low_angle_th=0, lane_offset=0):
"""
Check if a given vehicle is an obstacle in our way. To this end we take
into account the road and lane the target vehicle is on and run a
geometry test to check if the target vehicle is under a certain distance
in front of our ego vehicle. We also check the next waypoint, just to be
sure there's not a sudden road id change.
WARNING: This method is an approximation that could fail for very large
vehicles, which center is actually on a different lane but their
extension falls within the ego vehicle lane. Also, make sure to remove
the ego vehicle from the list. Lane offset is set to +1 for right lanes
and -1 for left lanes, but this has to be inverted if lane values are
negative.
:param ego_wpt: waypoint of ego-vehicle
:param ego_log: location of ego-vehicle
:param vehicle_list: list of potential obstacle to check
:param proximity_th: threshold for the agent to be alerted of
a possible collision
:param up_angle_th: upper threshold for angle
:param low_angle_th: lower threshold for angle
:param lane_offset: for right and left lane changes
:return: a tuple given by (bool_flag, vehicle, distance), where:
- bool_flag is True if there is a vehicle ahead blocking us
and False otherwise
- vehicle is the blocker object itself
- distance is the meters separating the two vehicles
"""
# Get the right offset
if ego_wpt.lane_id < 0 and lane_offset != 0:
lane_offset *= -1
for target_vehicle in vehicle_list:
target_vehicle_loc = target_vehicle.get_location()
# If the object is not in our next or current lane it's not an obstacle
target_wpt = self._map.get_waypoint(target_vehicle_loc)
if target_wpt.road_id != ego_wpt.road_id or \
target_wpt.lane_id != ego_wpt.lane_id + lane_offset:
next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=5)[0]
if target_wpt.road_id != next_wpt.road_id or \
target_wpt.lane_id != next_wpt.lane_id + lane_offset:
continue
if is_within_distance(target_vehicle_loc, ego_loc,
self._vehicle.get_transform().rotation.yaw,
proximity_th, up_angle_th, low_angle_th):
return (True, target_vehicle, compute_distance(target_vehicle_loc, ego_loc))
return (False, None, -1)
def _is_vehicle_hazard(self, vehicle_list):
"""
:param vehicle_list: list of potential obstacle to check
:return: a tuple given by (bool_flag, vehicle), where
- bool_flag is True if there is a vehicle ahead blocking us
and False otherwise
- vehicle is the blocker object itself
"""
ego_vehicle_location = self._vehicle.get_location()
ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location)
for target_vehicle in vehicle_list:
# do not account for the ego vehicle
if target_vehicle.id == self._vehicle.id:
continue
# if the object is not in our lane it's not an obstacle
target_vehicle_waypoint = self._map.get_waypoint(target_vehicle.get_location())
if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \
target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id:
continue
if is_within_distance_ahead(target_vehicle.get_transform(),
self._vehicle.get_transform(),
self._proximity_vehicle_threshold):
return (True, target_vehicle)
return (False, None)
@staticmethod
def emergency_stop():
"""
Send an emergency stop command to the vehicle
:return: control for braking
"""
control = carla.VehicleControl()
control.steer = 0.0
control.throttle = 0.0
control.brake = 1.0
control.hand_brake = False
return control
================================================
FILE: agents/navigation/basic_agent.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module implements an agent that roams around a track following random
waypoints and avoiding other vehicles.
The agent also responds to traffic lights. """
import carla
from agents.navigation.agent import Agent, AgentState
from agents.navigation.local_planner import LocalPlanner
from agents.navigation.global_route_planner import GlobalRoutePlanner
from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
class BasicAgent(Agent):
"""
BasicAgent implements a basic agent that navigates scenes to reach a given
target destination. This agent respects traffic lights and other vehicles.
"""
def __init__(self, vehicle, target_speed=20):
"""
:param vehicle: actor to apply to local planner logic onto
"""
super(BasicAgent, self).__init__(vehicle)
self._proximity_tlight_threshold = 5.0 # meters
self._proximity_vehicle_threshold = 10.0 # meters
self._state = AgentState.NAVIGATING
args_lateral_dict = {
'K_P': 1,
'K_D': 0.4,
'K_I': 0,
'dt': 1.0/20.0}
self._local_planner = LocalPlanner(
self._vehicle, opt_dict={'target_speed' : target_speed,
'lateral_control_dict':args_lateral_dict})
self._hop_resolution = 2.0
self._path_seperation_hop = 2
self._path_seperation_threshold = 0.5
self._target_speed = target_speed
self._grp = None
def set_destination(self, location):
"""
This method creates a list of waypoints from agent's position to destination location
based on the route returned by the global router
"""
start_waypoint = self._map.get_waypoint(self._vehicle.get_location())
end_waypoint = self._map.get_waypoint(
carla.Location(location[0], location[1], location[2]))
route_trace = self._trace_route(start_waypoint, end_waypoint)
self._local_planner.set_global_plan(route_trace)
def _trace_route(self, start_waypoint, end_waypoint):
"""
This method sets up a global router and returns the optimal route
from start_waypoint to end_waypoint
"""
# Setting up global router
if self._grp is None:
dao = GlobalRoutePlannerDAO(self._vehicle.get_world().get_map(), self._hop_resolution)
grp = GlobalRoutePlanner(dao)
grp.setup()
self._grp = grp
# Obtain route plan
route = self._grp.trace_route(
start_waypoint.transform.location,
end_waypoint.transform.location)
return route
def run_step(self, debug=False):
"""
Execute one step of navigation.
:return: carla.VehicleControl
"""
# is there an obstacle in front of us?
hazard_detected = False
# retrieve relevant elements for safe navigation, i.e.: traffic lights
# and other vehicles
actor_list = self._world.get_actors()
vehicle_list = actor_list.filter("*vehicle*")
lights_list = actor_list.filter("*traffic_light*")
# check possible obstacles
vehicle_state, vehicle = self._is_vehicle_hazard(vehicle_list)
if vehicle_state:
if debug:
print('!!! VEHICLE BLOCKING AHEAD [{}])'.format(vehicle.id))
self._state = AgentState.BLOCKED_BY_VEHICLE
hazard_detected = True
# check for the state of the traffic lights
light_state, traffic_light = self._is_light_red(lights_list)
if light_state:
if debug:
print('=== RED LIGHT AHEAD [{}])'.format(traffic_light.id))
self._state = AgentState.BLOCKED_RED_LIGHT
hazard_detected = True
if hazard_detected:
control = self.emergency_stop()
else:
self._state = AgentState.NAVIGATING
# standard local planner behavior
control = self._local_planner.run_step(debug=debug)
return control
def done(self):
"""
Check whether the agent has reached its destination.
:return bool
"""
return self._local_planner.done()
================================================
FILE: agents/navigation/behavior_agent.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module implements an agent that roams around a track following random
waypoints and avoiding other vehicles. The agent also responds to traffic lights,
traffic signs, and has different possible configurations. """
import random
import numpy as np
import carla
from agents.navigation.agent import Agent
from agents.navigation.local_planner_behavior import LocalPlanner, RoadOption
from agents.navigation.global_route_planner import GlobalRoutePlanner
from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
from agents.navigation.types_behavior import Cautious, Aggressive, Normal
from agents.tools.misc import get_speed, positive
class BehaviorAgent(Agent):
"""
BehaviorAgent implements an agent that navigates scenes to reach a given
target destination, by computing the shortest possible path to it.
This agent can correctly follow traffic signs, speed limitations,
traffic lights, while also taking into account nearby vehicles. Lane changing
decisions can be taken by analyzing the surrounding environment,
such as overtaking or tailgating avoidance. Adding to these are possible
behaviors, the agent can also keep safety distance from a car in front of it
by tracking the instantaneous time to collision and keeping it in a certain range.
Finally, different sets of behaviors are encoded in the agent, from cautious
to a more aggressive ones.
"""
def __init__(self, vehicle, ignore_traffic_light=False, behavior='normal'):
"""
Constructor method.
:param vehicle: actor to apply to local planner logic onto
:param ignore_traffic_light: boolean to ignore any traffic light
:param behavior: type of agent to apply
"""
super(BehaviorAgent, self).__init__(vehicle)
self.vehicle = vehicle
self.ignore_traffic_light = ignore_traffic_light
self._local_planner = LocalPlanner(self)
self._grp = None
self.look_ahead_steps = 0
# Vehicle information
self.speed = 0
self.speed_limit = 0
self.direction = None
self.incoming_direction = None
self.incoming_waypoint = None
self.start_waypoint = None
self.end_waypoint = None
self.is_at_traffic_light = 0
self.light_state = "Green"
self.light_id_to_ignore = -1
self.min_speed = 5
self.behavior = None
self._sampling_resolution = 4.5
# Parameters for agent behavior
if behavior == 'cautious':
self.behavior = Cautious()
elif behavior == 'normal':
self.behavior = Normal()
elif behavior == 'aggressive':
self.behavior = Aggressive()
def update_information(self, world):
"""
This method updates the information regarding the ego
vehicle based on the surrounding world.
:param world: carla.world object
"""
self.speed = get_speed(self.vehicle)
self.speed_limit = world.player.get_speed_limit()
self._local_planner.set_speed(self.speed_limit)
self.direction = self._local_planner.target_road_option
if self.direction is None:
self.direction = RoadOption.LANEFOLLOW
self.look_ahead_steps = int((self.speed_limit) / 10)
self.incoming_waypoint, self.incoming_direction = self._local_planner.get_incoming_waypoint_and_direction(
steps=self.look_ahead_steps)
if self.incoming_direction is None:
self.incoming_direction = RoadOption.LANEFOLLOW
self.is_at_traffic_light = world.player.is_at_traffic_light()
if self.ignore_traffic_light:
self.light_state = "Green"
else:
# This method also includes stop signs and intersections.
self.light_state = str(self.vehicle.get_traffic_light_state())
def set_destination(self, start_location, end_location, clean=False):
"""
This method creates a list of waypoints from agent's position to destination location
based on the route returned by the global router.
:param start_location: initial position
:param end_location: final position
:param clean: boolean to clean the waypoint queue
"""
if clean:
self._local_planner.waypoints_queue.clear()
self.start_waypoint = self._map.get_waypoint(start_location)
self.end_waypoint = self._map.get_waypoint(end_location)
route_trace = self._trace_route(self.start_waypoint, self.end_waypoint)
self._local_planner.set_global_plan(route_trace, clean)
def reroute(self, spawn_points):
"""
This method implements re-routing for vehicles approaching its destination.
It finds a new target and computes another path to reach it.
:param spawn_points: list of possible destinations for the agent
"""
print("Target almost reached, setting new destination...")
random.shuffle(spawn_points)
new_start = self._local_planner.waypoints_queue[-1][0].transform.location
destination = spawn_points[0].location if spawn_points[0].location != new_start else spawn_points[1].location
print("New destination: " + str(destination))
self.set_destination(new_start, destination)
def _trace_route(self, start_waypoint, end_waypoint):
"""
This method sets up a global router and returns the
optimal route from start_waypoint to end_waypoint.
:param start_waypoint: initial position
:param end_waypoint: final position
"""
# Setting up global router
if self._grp is None:
wld = self.vehicle.get_world()
dao = GlobalRoutePlannerDAO(
wld.get_map(), sampling_resolution=self._sampling_resolution)
grp = GlobalRoutePlanner(dao)
grp.setup()
self._grp = grp
# Obtain route plan
route = self._grp.trace_route(
start_waypoint.transform.location,
end_waypoint.transform.location)
return route
def traffic_light_manager(self, waypoint):
"""
This method is in charge of behaviors for red lights and stops.
WARNING: What follows is a proxy to avoid having a car brake after running a yellow light.
This happens because the car is still under the influence of the semaphore,
even after passing it. So, the semaphore id is temporarely saved to
ignore it and go around this issue, until the car is near a new one.
:param waypoint: current waypoint of the agent
"""
light_id = self.vehicle.get_traffic_light().id if self.vehicle.get_traffic_light() is not None else -1
if self.light_state == "Red":
if not waypoint.is_junction and (self.light_id_to_ignore != light_id or light_id == -1):
return 1
elif waypoint.is_junction and light_id != -1:
self.light_id_to_ignore = light_id
if self.light_id_to_ignore != light_id:
self.light_id_to_ignore = -1
return 0
def _overtake(self, location, waypoint, vehicle_list):
"""
This method is in charge of overtaking behaviors.
:param location: current location of the agent
:param waypoint: current waypoint of the agent
:param vehicle_list: list of all the nearby vehicles
"""
left_turn = waypoint.left_lane_marking.lane_change
right_turn = waypoint.right_lane_marking.lane_change
left_wpt = waypoint.get_left_lane()
right_wpt = waypoint.get_right_lane()
if (left_turn == carla.LaneChange.Left or left_turn ==
carla.LaneChange.Both) and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving:
new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=180, lane_offset=-1)
if not new_vehicle_state:
print("Overtaking to the left!")
self.behavior.overtake_counter = 200
self.set_destination(left_wpt.transform.location,
self.end_waypoint.transform.location, clean=True)
elif right_turn == carla.LaneChange.Right and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving:
new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=180, lane_offset=1)
if not new_vehicle_state:
print("Overtaking to the right!")
self.behavior.overtake_counter = 200
self.set_destination(right_wpt.transform.location,
self.end_waypoint.transform.location, clean=True)
def _tailgating(self, location, waypoint, vehicle_list):
"""
This method is in charge of tailgating behaviors.
:param location: current location of the agent
:param waypoint: current waypoint of the agent
:param vehicle_list: list of all the nearby vehicles
"""
left_turn = waypoint.left_lane_marking.lane_change
right_turn = waypoint.right_lane_marking.lane_change
left_wpt = waypoint.get_left_lane()
right_wpt = waypoint.get_right_lane()
behind_vehicle_state, behind_vehicle, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, low_angle_th=160)
if behind_vehicle_state and self.speed < get_speed(behind_vehicle):
if (right_turn == carla.LaneChange.Right or right_turn ==
carla.LaneChange.Both) and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving:
new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=1)
if not new_vehicle_state:
print("Tailgating, moving to the right!")
self.behavior.tailgate_counter = 200
self.set_destination(right_wpt.transform.location,
self.end_waypoint.transform.location, clean=True)
elif left_turn == carla.LaneChange.Left and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving:
new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=-1)
if not new_vehicle_state:
print("Tailgating, moving to the left!")
self.behavior.tailgate_counter = 200
self.set_destination(left_wpt.transform.location,
self.end_waypoint.transform.location, clean=True)
def collision_and_car_avoid_manager(self, location, waypoint):
"""
This module is in charge of warning in case of a collision
and managing possible overtaking or tailgating chances.
:param location: current location of the agent
:param waypoint: current waypoint of the agent
:return vehicle_state: True if there is a vehicle nearby, False if not
:return vehicle: nearby vehicle
:return distance: distance to nearby vehicle
"""
vehicle_list = self._world.get_actors().filter("*vehicle*")
def dist(v): return v.get_location().distance(waypoint.transform.location)
vehicle_list = [v for v in vehicle_list if dist(v) < 45 and v.id != self.vehicle.id]
if self.direction == RoadOption.CHANGELANELEFT:
vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard(
waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=-1)
elif self.direction == RoadOption.CHANGELANERIGHT:
vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard(
waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=1)
else:
vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard(
waypoint, location, vehicle_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=30)
# Check for overtaking
if vehicle_state and self.direction == RoadOption.LANEFOLLOW and \
not waypoint.is_junction and self.speed > 10 \
and self.behavior.overtake_counter == 0 and self.speed > get_speed(vehicle):
self._overtake(location, waypoint, vehicle_list)
# Check for tailgating
elif not vehicle_state and self.direction == RoadOption.LANEFOLLOW \
and not waypoint.is_junction and self.speed > 10 \
and self.behavior.tailgate_counter == 0:
self._tailgating(location, waypoint, vehicle_list)
return vehicle_state, vehicle, distance
def pedestrian_avoid_manager(self, location, waypoint):
"""
This module is in charge of warning in case of a collision
with any pedestrian.
:param location: current location of the agent
:param waypoint: current waypoint of the agent
:return vehicle_state: True if there is a walker nearby, False if not
:return vehicle: nearby walker
:return distance: distance to nearby walker
"""
walker_list = self._world.get_actors().filter("*walker.pedestrian*")
def dist(w): return w.get_location().distance(waypoint.transform.location)
walker_list = [w for w in walker_list if dist(w) < 10]
if self.direction == RoadOption.CHANGELANELEFT:
walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=90, lane_offset=-1)
elif self.direction == RoadOption.CHANGELANERIGHT:
walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=90, lane_offset=1)
else:
walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max(
self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=60)
return walker_state, walker, distance
def car_following_manager(self, vehicle, distance, debug=False):
"""
Module in charge of car-following behaviors when there's
someone in front of us.
:param vehicle: car to follow
:param distance: distance from vehicle
:param debug: boolean for debugging
:return control: carla.VehicleControl
"""
vehicle_speed = get_speed(vehicle)
delta_v = max(1, (self.speed - vehicle_speed) / 3.6)
ttc = distance / delta_v if delta_v != 0 else distance / np.nextafter(0., 1.)
# Under safety time distance, slow down.
if self.behavior.safety_time > ttc > 0.0:
control = self._local_planner.run_step(
target_speed=min(positive(vehicle_speed - self.behavior.speed_decrease),
min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist)), debug=debug)
# Actual safety distance area, try to follow the speed of the vehicle in front.
elif 2 * self.behavior.safety_time > ttc >= self.behavior.safety_time:
control = self._local_planner.run_step(
target_speed=min(max(self.min_speed, vehicle_speed),
min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist)), debug=debug)
# Normal behavior.
else:
control = self._local_planner.run_step(
target_speed= min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist), debug=debug)
return control
def run_step(self, debug=False):
"""
Execute one step of navigation.
:param debug: boolean for debugging
:return control: carla.VehicleControl
"""
control = None
if self.behavior.tailgate_counter > 0:
self.behavior.tailgate_counter -= 1
if self.behavior.overtake_counter > 0:
self.behavior.overtake_counter -= 1
ego_vehicle_loc = self.vehicle.get_location()
ego_vehicle_wp = self._map.get_waypoint(ego_vehicle_loc)
# 1: Red lights and stops behavior
if self.traffic_light_manager(ego_vehicle_wp) != 0:
return self.emergency_stop()
# 2.1: Pedestrian avoidancd behaviors
walker_state, walker, w_distance = self.pedestrian_avoid_manager(
ego_vehicle_loc, ego_vehicle_wp)
if walker_state:
# Distance is computed from the center of the two cars,
# we use bounding boxes to calculate the actual distance
distance = w_distance - max(
walker.bounding_box.extent.y, walker.bounding_box.extent.x) - max(
self.vehicle.bounding_box.extent.y, self.vehicle.bounding_box.extent.x)
# Emergency brake if the car is very close.
if distance < self.behavior.braking_distance:
return self.emergency_stop()
# 2.2: Car following behaviors
vehicle_state, vehicle, distance = self.collision_and_car_avoid_manager(
ego_vehicle_loc, ego_vehicle_wp)
if vehicle_state:
# Distance is computed from the center of the two cars,
# we use bounding boxes to calculate the actual distance
distance = distance - max(
vehicle.bounding_box.extent.y, vehicle.bounding_box.extent.x) - max(
self.vehicle.bounding_box.extent.y, self.vehicle.bounding_box.extent.x)
# Emergency brake if the car is very close.
if distance < self.behavior.braking_distance:
return self.emergency_stop()
else:
control = self.car_following_manager(vehicle, distance)
# 4: Intersection behavior
# Checking if there's a junction nearby to slow down
elif self.incoming_waypoint.is_junction and (self.incoming_direction == RoadOption.LEFT or self.incoming_direction == RoadOption.RIGHT):
control = self._local_planner.run_step(
target_speed=min(self.behavior.max_speed, self.speed_limit - 5), debug=debug)
# 5: Normal behavior
# Calculate controller based on no turn, traffic light or vehicle in front
else:
control = self._local_planner.run_step(
target_speed= min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist), debug=debug)
return control
================================================
FILE: agents/navigation/controller.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module contains PID controllers to perform lateral and longitudinal control. """
from collections import deque
import math
import numpy as np
import carla
from agents.tools.misc import get_speed
class VehiclePIDController():
"""
VehiclePIDController is the combination of two PID controllers
(lateral and longitudinal) to perform the
low level control a vehicle from client side
"""
def __init__(self, vehicle, args_lateral, args_longitudinal, max_throttle=0.75, max_brake=0.3, max_steering=0.8):
"""
Constructor method.
:param vehicle: actor to apply to local planner logic onto
:param args_lateral: dictionary of arguments to set the lateral PID controller
using the following semantics:
K_P -- Proportional term
K_D -- Differential term
K_I -- Integral term
:param args_longitudinal: dictionary of arguments to set the longitudinal
PID controller using the following semantics:
K_P -- Proportional term
K_D -- Differential term
K_I -- Integral term
"""
self.max_brake = max_brake
self.max_throt = max_throttle
self.max_steer = max_steering
self._vehicle = vehicle
self._world = self._vehicle.get_world()
self.past_steering = self._vehicle.get_control().steer
self._lon_controller = PIDLongitudinalController(self._vehicle, **args_longitudinal)
self._lat_controller = PIDLateralController(self._vehicle, **args_lateral)
def run_step(self, target_speed, waypoint):
"""
Execute one step of control invoking both lateral and longitudinal
PID controllers to reach a target waypoint
at a given target_speed.
:param target_speed: desired vehicle speed
:param waypoint: target location encoded as a waypoint
:return: distance (in meters) to the waypoint
"""
acceleration = self._lon_controller.run_step(target_speed)
current_steering = self._lat_controller.run_step(waypoint)
control = carla.VehicleControl()
if acceleration >= 0.0:
control.throttle = min(acceleration, self.max_throt)
control.brake = 0.0
else:
control.throttle = 0.0
control.brake = min(abs(acceleration), self.max_brake)
# Steering regulation: changes cannot happen abruptly, can't steer too much.
if current_steering > self.past_steering + 0.1:
current_steering = self.past_steering + 0.1
elif current_steering < self.past_steering - 0.1:
current_steering = self.past_steering - 0.1
if current_steering >= 0:
steering = min(self.max_steer, current_steering)
else:
steering = max(-self.max_steer, current_steering)
control.steer = steering
control.hand_brake = False
control.manual_gear_shift = False
self.past_steering = steering
return control
class PIDLongitudinalController():
"""
PIDLongitudinalController implements longitudinal control using a PID.
"""
def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03):
"""
Constructor method.
:param vehicle: actor to apply to local planner logic onto
:param K_P: Proportional term
:param K_D: Differential term
:param K_I: Integral term
:param dt: time differential in seconds
"""
self._vehicle = vehicle
self._k_p = K_P
self._k_d = K_D
self._k_i = K_I
self._dt = dt
self._error_buffer = deque(maxlen=10)
def run_step(self, target_speed, debug=False):
"""
Execute one step of longitudinal control to reach a given target speed.
:param target_speed: target speed in Km/h
:param debug: boolean for debugging
:return: throttle control
"""
current_speed = get_speed(self._vehicle)
if debug:
print('Current speed = {}'.format(current_speed))
return self._pid_control(target_speed, current_speed)
def _pid_control(self, target_speed, current_speed):
"""
Estimate the throttle/brake of the vehicle based on the PID equations
:param target_speed: target speed in Km/h
:param current_speed: current speed of the vehicle in Km/h
:return: throttle/brake control
"""
error = target_speed - current_speed
self._error_buffer.append(error)
if len(self._error_buffer) >= 2:
_de = (self._error_buffer[-1] - self._error_buffer[-2]) / self._dt
_ie = sum(self._error_buffer) * self._dt
else:
_de = 0.0
_ie = 0.0
return np.clip((self._k_p * error) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)
class PIDLateralController():
"""
PIDLateralController implements lateral control using a PID.
"""
def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03):
"""
Constructor method.
:param vehicle: actor to apply to local planner logic onto
:param K_P: Proportional term
:param K_D: Differential term
:param K_I: Integral term
:param dt: time differential in seconds
"""
self._vehicle = vehicle
self._k_p = K_P
self._k_d = K_D
self._k_i = K_I
self._dt = dt
self._e_buffer = deque(maxlen=10)
def run_step(self, waypoint):
"""
Execute one step of lateral control to steer
the vehicle towards a certain waypoin.
:param waypoint: target waypoint
:return: steering control in the range [-1, 1] where:
-1 maximum steering to left
+1 maximum steering to right
"""
return self._pid_control(waypoint, self._vehicle.get_transform())
def _pid_control(self, waypoint, vehicle_transform):
"""
Estimate the steering angle of the vehicle based on the PID equations
:param waypoint: target waypoint
:param vehicle_transform: current transform of the vehicle
:return: steering control in the range [-1, 1]
"""
v_begin = vehicle_transform.location
v_end = v_begin + carla.Location(x=math.cos(math.radians(vehicle_transform.rotation.yaw)),
y=math.sin(math.radians(vehicle_transform.rotation.yaw)))
v_vec = np.array([v_end.x - v_begin.x, v_end.y - v_begin.y, 0.0])
w_vec = np.array([waypoint.transform.location.x -
v_begin.x, waypoint.transform.location.y -
v_begin.y, 0.0])
_dot = math.acos(np.clip(np.dot(w_vec, v_vec) /
(np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0))
_cross = np.cross(v_vec, w_vec)
if _cross[2] < 0:
_dot *= -1.0
self._e_buffer.append(_dot)
if len(self._e_buffer) >= 2:
_de = (self._e_buffer[-1] - self._e_buffer[-2]) / self._dt
_ie = sum(self._e_buffer) * self._dt
else:
_de = 0.0
_ie = 0.0
return np.clip((self._k_p * _dot) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0)
================================================
FILE: agents/navigation/global_route_planner.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
This module provides GlobalRoutePlanner implementation.
"""
import math
import numpy as np
import networkx as nx
import carla
from agents.navigation.local_planner import RoadOption
from agents.tools.misc import vector
class GlobalRoutePlanner(object):
"""
This class provides a very high level route plan.
Instantiate the class by passing a reference to
A GlobalRoutePlannerDAO object.
"""
def __init__(self, dao):
"""
Constructor
"""
self._dao = dao
self._topology = None
self._graph = None
self._id_map = None
self._road_id_to_edge = None
self._intersection_end_node = -1
self._previous_decision = RoadOption.VOID
def setup(self):
"""
Performs initial server data lookup for detailed topology
and builds graph representation of the world map.
"""
self._topology = self._dao.get_topology()
self._graph, self._id_map, self._road_id_to_edge = self._build_graph()
self._find_loose_ends()
self._lane_change_link()
def _build_graph(self):
"""
This function builds a networkx graph representation of topology.
The topology is read from self._topology.
graph node properties:
vertex - (x,y,z) position in world map
graph edge properties:
entry_vector - unit vector along tangent at entry point
exit_vector - unit vector along tangent at exit point
net_vector - unit vector of the chord from entry to exit
intersection - boolean indicating if the edge belongs to an
intersection
return : graph -> networkx graph representing the world map,
id_map-> mapping from (x,y,z) to node id
road_id_to_edge-> map from road id to edge in the graph
"""
graph = nx.DiGraph()
id_map = dict() # Map with structure {(x,y,z): id, ... }
road_id_to_edge = dict() # Map with structure {road_id: {lane_id: edge, ... }, ... }
for segment in self._topology:
entry_xyz, exit_xyz = segment['entryxyz'], segment['exitxyz']
path = segment['path']
entry_wp, exit_wp = segment['entry'], segment['exit']
intersection = entry_wp.is_junction
road_id, section_id, lane_id = entry_wp.road_id, entry_wp.section_id, entry_wp.lane_id
for vertex in entry_xyz, exit_xyz:
# Adding unique nodes and populating id_map
if vertex not in id_map:
new_id = len(id_map)
id_map[vertex] = new_id
graph.add_node(new_id, vertex=vertex)
n1 = id_map[entry_xyz]
n2 = id_map[exit_xyz]
if road_id not in road_id_to_edge:
road_id_to_edge[road_id] = dict()
if section_id not in road_id_to_edge[road_id]:
road_id_to_edge[road_id][section_id] = dict()
road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)
entry_carla_vector = entry_wp.transform.rotation.get_forward_vector()
exit_carla_vector = exit_wp.transform.rotation.get_forward_vector()
# Adding edge with attributes
graph.add_edge(
n1, n2,
length=len(path) + 1, path=path,
entry_waypoint=entry_wp, exit_waypoint=exit_wp,
entry_vector=np.array(
[entry_carla_vector.x, entry_carla_vector.y, entry_carla_vector.z]),
exit_vector=np.array(
[exit_carla_vector.x, exit_carla_vector.y, exit_carla_vector.z]),
net_vector=vector(entry_wp.transform.location, exit_wp.transform.location),
intersection=intersection, type=RoadOption.LANEFOLLOW)
return graph, id_map, road_id_to_edge
def _find_loose_ends(self):
"""
This method finds road segments that have an unconnected end, and
adds them to the internal graph representation
"""
count_loose_ends = 0
hop_resolution = self._dao.get_resolution()
for segment in self._topology:
end_wp = segment['exit']
exit_xyz = segment['exitxyz']
road_id, section_id, lane_id = end_wp.road_id, end_wp.section_id, end_wp.lane_id
if road_id in self._road_id_to_edge and section_id in self._road_id_to_edge[road_id] and lane_id in self._road_id_to_edge[road_id][section_id]:
pass
else:
count_loose_ends += 1
if road_id not in self._road_id_to_edge:
self._road_id_to_edge[road_id] = dict()
if section_id not in self._road_id_to_edge[road_id]:
self._road_id_to_edge[road_id][section_id] = dict()
n1 = self._id_map[exit_xyz]
n2 = -1*count_loose_ends
self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2)
next_wp = end_wp.next(hop_resolution)
path = []
while next_wp is not None and next_wp and next_wp[0].road_id == road_id and next_wp[0].section_id == section_id and next_wp[0].lane_id == lane_id:
path.append(next_wp[0])
next_wp = next_wp[0].next(hop_resolution)
if path:
n2_xyz = (path[-1].transform.location.x,
path[-1].transform.location.y,
path[-1].transform.location.z)
self._graph.add_node(n2, vertex=n2_xyz)
self._graph.add_edge(
n1, n2,
length=len(path) + 1, path=path,
entry_waypoint=end_wp, exit_waypoint=path[-1],
entry_vector=None, exit_vector=None, net_vector=None,
intersection=end_wp.is_junction, type=RoadOption.LANEFOLLOW)
def _localize(self, location):
"""
This function finds the road segment closest to given location
location : carla.Location to be localized in the graph
return : pair node ids representing an edge in the graph
"""
waypoint = self._dao.get_waypoint(location)
edge = None
try:
edge = self._road_id_to_edge[waypoint.road_id][waypoint.section_id][waypoint.lane_id]
except KeyError:
print(
"Failed to localize! : ",
"Road id : ", waypoint.road_id,
"Section id : ", waypoint.section_id,
"Lane id : ", waypoint.lane_id,
"Location : ", waypoint.transform.location.x,
waypoint.transform.location.y)
return edge
def _lane_change_link(self):
"""
This method places zero cost links in the topology graph
representing availability of lane changes.
"""
for segment in self._topology:
left_found, right_found = False, False
for waypoint in segment['path']:
if not segment['entry'].is_junction:
next_waypoint, next_road_option, next_segment = None, None, None
if waypoint.right_lane_marking.lane_change & carla.LaneChange.Right and not right_found:
next_waypoint = waypoint.get_right_lane()
if next_waypoint is not None and next_waypoint.lane_type == carla.LaneType.Driving and waypoint.road_id == next_waypoint.road_id:
next_road_option = RoadOption.CHANGELANERIGHT
next_segment = self._localize(next_waypoint.transform.location)
if next_segment is not None:
self._graph.add_edge(
self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,
exit_waypoint=next_waypoint, intersection=False, exit_vector=None,
path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)
right_found = True
if waypoint.left_lane_marking.lane_change & carla.LaneChange.Left and not left_found:
next_waypoint = waypoint.get_left_lane()
if next_waypoint is not None and next_waypoint.lane_type == carla.LaneType.Driving and waypoint.road_id == next_waypoint.road_id:
next_road_option = RoadOption.CHANGELANELEFT
next_segment = self._localize(next_waypoint.transform.location)
if next_segment is not None:
self._graph.add_edge(
self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint,
exit_waypoint=next_waypoint, intersection=False, exit_vector=None,
path=[], length=0, type=next_road_option, change_waypoint=next_waypoint)
left_found = True
if left_found and right_found:
break
def _distance_heuristic(self, n1, n2):
"""
Distance heuristic calculator for path searching
in self._graph
"""
l1 = np.array(self._graph.nodes[n1]['vertex'])
l2 = np.array(self._graph.nodes[n2]['vertex'])
return np.linalg.norm(l1-l2)
def _path_search(self, origin, destination):
"""
This function finds the shortest path connecting origin and destination
using A* search with distance heuristic.
origin : carla.Location object of start position
destination : carla.Location object of of end position
return : path as list of node ids (as int) of the graph self._graph
connecting origin and destination
"""
start, end = self._localize(origin), self._localize(destination)
route = nx.astar_path(
self._graph, source=start[0], target=end[0],
heuristic=self._distance_heuristic, weight='length')
route.append(end[1])
return route
def _successive_last_intersection_edge(self, index, route):
"""
This method returns the last successive intersection edge
from a starting index on the route.
This helps moving past tiny intersection edges to calculate
proper turn decisions.
"""
last_intersection_edge = None
last_node = None
for node1, node2 in [(route[i], route[i+1]) for i in range(index, len(route)-1)]:
candidate_edge = self._graph.edges[node1, node2]
if node1 == route[index]:
last_intersection_edge = candidate_edge
if candidate_edge['type'] == RoadOption.LANEFOLLOW and candidate_edge['intersection']:
last_intersection_edge = candidate_edge
last_node = node2
else:
break
return last_node, last_intersection_edge
def _turn_decision(self, index, route, threshold=math.radians(35)):
"""
This method returns the turn decision (RoadOption) for pair of edges
around current index of route list
"""
decision = None
previous_node = route[index-1]
current_node = route[index]
next_node = route[index+1]
next_edge = self._graph.edges[current_node, next_node]
if index > 0:
if self._previous_decision != RoadOption.VOID and self._intersection_end_node > 0 and self._intersection_end_node != previous_node and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection']:
decision = self._previous_decision
else:
self._intersection_end_node = -1
current_edge = self._graph.edges[previous_node, current_node]
calculate_turn = current_edge['type'] == RoadOption.LANEFOLLOW and not current_edge[
'intersection'] and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection']
if calculate_turn:
last_node, tail_edge = self._successive_last_intersection_edge(index, route)
self._intersection_end_node = last_node
if tail_edge is not None:
next_edge = tail_edge
cv, nv = current_edge['exit_vector'], next_edge['exit_vector']
if cv is None or nv is None:
return next_edge['type']
cross_list = []
for neighbor in self._graph.successors(current_node):
select_edge = self._graph.edges[current_node, neighbor]
if select_edge['type'] == RoadOption.LANEFOLLOW:
if neighbor != route[index+1]:
sv = select_edge['net_vector']
cross_list.append(np.cross(cv, sv)[2])
next_cross = np.cross(cv, nv)[2]
deviation = math.acos(np.clip(
np.dot(cv, nv)/(np.linalg.norm(cv)*np.linalg.norm(nv)), -1.0, 1.0))
if not cross_list:
cross_list.append(0)
if deviation < threshold:
decision = RoadOption.STRAIGHT
elif cross_list and next_cross < min(cross_list):
decision = RoadOption.LEFT
elif cross_list and next_cross > max(cross_list):
decision = RoadOption.RIGHT
elif next_cross < 0:
decision = RoadOption.LEFT
elif next_cross > 0:
decision = RoadOption.RIGHT
else:
decision = next_edge['type']
else:
decision = next_edge['type']
self._previous_decision = decision
return decision
def abstract_route_plan(self, origin, destination):
"""
The following function generates the route plan based on
origin : carla.Location object of the route's start position
destination : carla.Location object of the route's end position
return : list of turn by turn navigation decisions as
agents.navigation.local_planner.RoadOption elements
Possible values are STRAIGHT, LEFT, RIGHT, LANEFOLLOW, VOID
CHANGELANELEFT, CHANGELANERIGHT
"""
route = self._path_search(origin, destination)
plan = []
for i in range(len(route) - 1):
road_option = self._turn_decision(i, route)
plan.append(road_option)
return plan
def _find_closest_in_list(self, current_waypoint, waypoint_list):
min_distance = float('inf')
closest_index = -1
for i, waypoint in enumerate(waypoint_list):
distance = waypoint.transform.location.distance(
current_waypoint.transform.location)
if distance < min_distance:
min_distance = distance
closest_index = i
return closest_index
def trace_route(self, origin, destination):
"""
This method returns list of (carla.Waypoint, RoadOption)
from origin to destination
"""
route_trace = []
route = self._path_search(origin, destination)
current_waypoint = self._dao.get_waypoint(origin)
destination_waypoint = self._dao.get_waypoint(destination)
resolution = self._dao.get_resolution()
for i in range(len(route) - 1):
road_option = self._turn_decision(i, route)
edge = self._graph.edges[route[i], route[i+1]]
path = []
if edge['type'] != RoadOption.LANEFOLLOW and edge['type'] != RoadOption.VOID:
route_trace.append((current_waypoint, road_option))
exit_wp = edge['exit_waypoint']
n1, n2 = self._road_id_to_edge[exit_wp.road_id][exit_wp.section_id][exit_wp.lane_id]
next_edge = self._graph.edges[n1, n2]
if next_edge['path']:
closest_index = self._find_closest_in_list(current_waypoint, next_edge['path'])
closest_index = min(len(next_edge['path'])-1, closest_index+5)
current_waypoint = next_edge['path'][closest_index]
else:
current_waypoint = next_edge['exit_waypoint']
route_trace.append((current_waypoint, road_option))
else:
path = path + [edge['entry_waypoint']] + edge['path'] + [edge['exit_waypoint']]
closest_index = self._find_closest_in_list(current_waypoint, path)
for waypoint in path[closest_index:]:
current_waypoint = waypoint
route_trace.append((current_waypoint, road_option))
if len(route)-i <= 2 and waypoint.transform.location.distance(destination) < 2*resolution:
break
elif len(route)-i <= 2 and current_waypoint.road_id == destination_waypoint.road_id and current_waypoint.section_id == destination_waypoint.section_id and current_waypoint.lane_id == destination_waypoint.lane_id:
destination_index = self._find_closest_in_list(destination_waypoint, path)
if closest_index > destination_index:
break
return route_trace
================================================
FILE: agents/navigation/global_route_planner_dao.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
"""
This module provides implementation for GlobalRoutePlannerDAO
"""
import numpy as np
class GlobalRoutePlannerDAO(object):
"""
This class is the data access layer for fetching data
from the carla server instance for GlobalRoutePlanner
"""
def __init__(self, wmap, sampling_resolution):
"""
Constructor method.
:param wmap: carla.world object
:param sampling_resolution: sampling distance between waypoints
"""
self._sampling_resolution = sampling_resolution
self._wmap = wmap
def get_topology(self):
"""
Accessor for topology.
This function retrieves topology from the server as a list of
road segments as pairs of waypoint objects, and processes the
topology into a list of dictionary objects.
:return topology: list of dictionary objects with the following attributes
entry - waypoint of entry point of road segment
entryxyz- (x,y,z) of entry point of road segment
exit - waypoint of exit point of road segment
exitxyz - (x,y,z) of exit point of road segment
path - list of waypoints separated by 1m from entry
to exit
"""
topology = []
# Retrieving waypoints to construct a detailed topology
for segment in self._wmap.get_topology():
wp1, wp2 = segment[0], segment[1]
l1, l2 = wp1.transform.location, wp2.transform.location
# Rounding off to avoid floating point imprecision
x1, y1, z1, x2, y2, z2 = np.round([l1.x, l1.y, l1.z, l2.x, l2.y, l2.z], 0)
wp1.transform.location, wp2.transform.location = l1, l2
seg_dict = dict()
seg_dict['entry'], seg_dict['exit'] = wp1, wp2
seg_dict['entryxyz'], seg_dict['exitxyz'] = (x1, y1, z1), (x2, y2, z2)
seg_dict['path'] = []
endloc = wp2.transform.location
if wp1.transform.location.distance(endloc) > self._sampling_resolution:
w = wp1.next(self._sampling_resolution)[0]
while w.transform.location.distance(endloc) > self._sampling_resolution:
seg_dict['path'].append(w)
w = w.next(self._sampling_resolution)[0]
else:
seg_dict['path'].append(wp1.next(self._sampling_resolution)[0])
topology.append(seg_dict)
return topology
def get_waypoint(self, location):
"""
The method returns waypoint at given location
:param location: vehicle location
:return waypoint: generated waypoint close to location
"""
waypoint = self._wmap.get_waypoint(location)
return waypoint
def get_resolution(self):
""" Accessor for self._sampling_resolution """
return self._sampling_resolution
================================================
FILE: agents/navigation/local_planner.py
================================================
# Copyright (c) # Copyright (c) 2018-2020 CVC.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module contains a local planner to perform low-level waypoint following based on PID controllers. """
from enum import Enum
from collections import deque
import random
import carla
from agents.navigation.controller import VehiclePIDController
from agents.tools.misc import draw_waypoints
class RoadOption(Enum):
"""
RoadOption represents the possible topological configurations when moving from a segment of lane to other.
"""
VOID = -1
LEFT = 1
RIGHT = 2
STRAIGHT = 3
LANEFOLLOW = 4
CHANGELANELEFT = 5
CHANGELANERIGHT = 6
class LocalPlanner(object):
"""
LocalPlanner implements the basic behavior of following a trajectory of waypoints that is generated on-the-fly.
The low-level motion of the vehicle is computed by using two PID controllers, one is used for the lateral control
and the other for the longitudinal control (cruise speed).
When multiple paths are available (intersections) this local planner makes a random choice.
"""
# minimum distance to target waypoint as a percentage (e.g. within 90% of
# total distance)
MIN_DISTANCE_PERCENTAGE = 0.9
def __init__(self, vehicle, opt_dict=None):
"""
:param vehicle: actor to apply to local planner logic onto
:param opt_dict: dictionary of arguments with the following semantics:
dt -- time difference between physics control in seconds. This is typically fixed from server side
using the arguments -benchmark -fps=F . In this case dt = 1/F
target_speed -- desired cruise speed in Km/h
sampling_radius -- search radius for next waypoints in seconds: e.g. 0.5 seconds ahead
lateral_control_dict -- dictionary of arguments to setup the lateral PID controller
{'K_P':, 'K_D':, 'K_I':, 'dt'}
longitudinal_control_dict -- dictionary of arguments to setup the longitudinal PID controller
{'K_P':, 'K_D':, 'K_I':, 'dt'}
"""
self._vehicle = vehicle
self._map = self._vehicle.get_world().get_map()
self._dt = None
self._target_speed = None
self._sampling_radius = None
self._min_distance = None
self._current_waypoint = None
self._target_road_option = None
self._next_waypoints = None
self.target_waypoint = None
self._vehicle_controller = None
self._global_plan = None
# queue with tuples of (waypoint, RoadOption)
self._waypoints_queue = deque(maxlen=20000)
self._buffer_size = 5
self._waypoint_buffer = deque(maxlen=self._buffer_size)
# initializing controller
self._init_controller(opt_dict)
def __del__(self):
if self._vehicle:
self._vehicle.destroy()
print("Destroying ego-vehicle!")
def reset_vehicle(self):
self._vehicle = None
print("Resetting ego-vehicle!")
def _init_controller(self, opt_dict):
"""
Controller initialization.
:param opt_dict: dictionary of arguments.
:return:
"""
# default params
self._dt = 1.0 / 20.0
self._target_speed = 20.0 # Km/h
self._sampling_radius = self._target_speed * 1 / 3.6 # 1 seconds horizon
self._min_distance = self._sampling_radius * self.MIN_DISTANCE_PERCENTAGE
self._max_brake = 0.3
self._max_throt = 0.75
self._max_steer = 0.8
args_lateral_dict = {
'K_P': 1.95,
'K_D': 0.2,
'K_I': 0.07,
'dt': self._dt}
args_longitudinal_dict = {
'K_P': 1.0,
'K_D': 0,
'K_I': 0.05,
'dt': self._dt}
# parameters overload
if opt_dict:
if 'dt' in opt_dict:
self._dt = opt_dict['dt']
if 'target_speed' in opt_dict:
self._target_speed = opt_dict['target_speed']
if 'sampling_radius' in opt_dict:
self._sampling_radius = self._target_speed * \
opt_dict['sampling_radius'] / 3.6
if 'lateral_control_dict' in opt_dict:
args_lateral_dict = opt_dict['lateral_control_dict']
if 'longitudinal_control_dict' in opt_dict:
args_longitudinal_dict = opt_dict['longitudinal_control_dict']
if 'max_throttle' in opt_dict:
self._max_throt = opt_dict['max_throttle']
if 'max_brake' in opt_dict:
self._max_brake = opt_dict['max_brake']
if 'max_steering' in opt_dict:
self._max_steer = opt_dict['max_steering']
self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
self._vehicle_controller = VehiclePIDController(self._vehicle,
args_lateral=args_lateral_dict,
args_longitudinal=args_longitudinal_dict,
max_throttle=self._max_throt,
max_brake=self._max_brake,
max_steering=self._max_steer,)
self._global_plan = False
# compute initial waypoints
self._waypoints_queue.append((self._current_waypoint.next(self._sampling_radius)[0], RoadOption.LANEFOLLOW))
self._target_road_option = RoadOption.LANEFOLLOW
# fill waypoint trajectory queue
self._compute_next_waypoints(k=200)
def set_speed(self, speed):
"""
Request new target speed.
:param speed: new target speed in Km/h
:return:
"""
self._target_speed = speed
def _compute_next_waypoints(self, k=1):
"""
Add new waypoints to the trajectory queue.
:param k: how many waypoints to compute
:return:
"""
# check we do not overflow the queue
available_entries = self._waypoints_queue.maxlen - len(self._waypoints_queue)
k = min(available_entries, k)
for _ in range(k):
last_waypoint = self._waypoints_queue[-1][0]
next_waypoints = list(last_waypoint.next(self._sampling_radius))
if len(next_waypoints) == 0:
break
elif len(next_waypoints) == 1:
# only one option available ==> lanefollowing
next_waypoint = next_waypoints[0]
road_option = RoadOption.LANEFOLLOW
else:
# random choice between the possible options
road_options_list = _retrieve_options(
next_waypoints, last_waypoint)
road_option = random.choice(road_options_list)
next_waypoint = next_waypoints[road_options_list.index(
road_option)]
self._waypoints_queue.append((next_waypoint, road_option))
def set_global_plan(self, current_plan):
"""
Resets the waypoint queue and buffer to match the new plan. Also
sets the global_plan flag to avoid creating more waypoints
:param current_plan: list of (carla.Waypoint, RoadOption)
:return:
"""
# Reset the queue
self._waypoints_queue.clear()
for elem in current_plan:
self._waypoints_queue.append(elem)
self._target_road_option = RoadOption.LANEFOLLOW
# and the buffer
self._waypoint_buffer.clear()
for _ in range(self._buffer_size):
if self._waypoints_queue:
self._waypoint_buffer.append(
self._waypoints_queue.popleft())
else:
break
self._global_plan = True
def run_step(self, debug=False):
"""
Execute one step of local planning which involves running the longitudinal and lateral PID controllers to
follow the waypoints trajectory.
:param debug: boolean flag to activate waypoints debugging
:return: control to be applied
"""
# not enough waypoints in the horizon? => add more!
if not self._global_plan and len(self._waypoints_queue) < int(self._waypoints_queue.maxlen * 0.5):
self._compute_next_waypoints(k=100)
if len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0:
control = carla.VehicleControl()
control.steer = 0.0
control.throttle = 0.0
control.brake = 1.0
control.hand_brake = False
control.manual_gear_shift = False
return control
# Buffering the waypoints
if not self._waypoint_buffer:
for _ in range(self._buffer_size):
if self._waypoints_queue:
self._waypoint_buffer.append(
self._waypoints_queue.popleft())
else:
break
# current vehicle waypoint
vehicle_transform = self._vehicle.get_transform()
self._current_waypoint = self._map.get_waypoint(vehicle_transform.location)
# target waypoint
self.target_waypoint, self._target_road_option = self._waypoint_buffer[0]
# move using PID controllers
control = self._vehicle_controller.run_step(self._target_speed, self.target_waypoint)
# purge the queue of obsolete waypoints
max_index = -1
for i, (waypoint, _) in enumerate(self._waypoint_buffer):
if waypoint.transform.location.distance(vehicle_transform.location) < self._min_distance:
max_index = i
if max_index >= 0:
for i in range(max_index + 1):
self._waypoint_buffer.popleft()
if debug:
draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], self._vehicle.get_location().z + 1.0)
return control
def done(self):
"""
Returns whether or not the planner has finished
:return: boolean
"""
return len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0
def _retrieve_options(list_waypoints, current_waypoint):
"""
Compute the type of connection between the current active waypoint and the multiple waypoints present in
list_waypoints. The result is encoded as a list of RoadOption enums.
:param list_waypoints: list with the possible target waypoints in case of multiple options
:param current_waypoint: current active waypoint
:return: list of RoadOption enums representing the type of connection from the active waypoint to each
candidate in list_waypoints
"""
options = []
for next_waypoint in list_waypoints:
# this is needed because something we are linking to
# the beggining of an intersection, therefore the
# variation in angle is small
next_next_waypoint = next_waypoint.next(3.0)[0]
link = _compute_connection(current_waypoint, next_next_waypoint)
options.append(link)
return options
def _compute_connection(current_waypoint, next_waypoint, threshold=35):
"""
Compute the type of topological connection between an active waypoint (current_waypoint) and a target waypoint
(next_waypoint).
:param current_waypoint: active waypoint
:param next_waypoint: target waypoint
:return: the type of topological connection encoded as a RoadOption enum:
RoadOption.STRAIGHT
RoadOption.LEFT
RoadOption.RIGHT
"""
n = next_waypoint.transform.rotation.yaw
n = n % 360.0
c = current_waypoint.transform.rotation.yaw
c = c % 360.0
diff_angle = (n - c) % 180.0
if diff_angle < threshold or diff_angle > (180 - threshold):
return RoadOption.STRAIGHT
elif diff_angle > 90.0:
return RoadOption.LEFT
else:
return RoadOption.RIGHT
================================================
FILE: agents/navigation/local_planner_behavior.py
================================================
#!/usr/bin/env python
# Copyright (c) 2018 Intel Labs.
# authors: German Ros (german.ros@intel.com)
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module contains a local planner to perform
low-level waypoint following based on PID controllers. """
from collections import deque
from enum import Enum
import carla
from agents.navigation.controller import VehiclePIDController
from agents.tools.misc import distance_vehicle, draw_waypoints
class RoadOption(Enum):
"""
RoadOption represents the possible topological configurations
when moving from a segment of lane to other.
"""
VOID = -1
LEFT = 1
RIGHT = 2
STRAIGHT = 3
LANEFOLLOW = 4
CHANGELANELEFT = 5
CHANGELANERIGHT = 6
class LocalPlanner(object):
"""
LocalPlanner implements the basic behavior of following a trajectory
of waypoints that is generated on-the-fly.
The low-level motion of the vehicle is computed by using two PID controllers,
one is used for the lateral control
and the other for the longitudinal control (cruise speed).
When multiple paths are available (intersections)
this local planner makes a random choice.
"""
# Minimum distance to target waypoint as a percentage
# (e.g. within 80% of total distance)
# FPS used for dt
FPS = 20
def __init__(self, agent):
"""
:param agent: agent that regulates the vehicle
:param vehicle: actor to apply to local planner logic onto
"""
self._vehicle = agent.vehicle
self._map = agent.vehicle.get_world().get_map()
self._target_speed = None
self.sampling_radius = None
self._min_distance = None
self._current_waypoint = None
self.target_road_option = None
self._next_waypoints = None
self.target_waypoint = None
self._vehicle_controller = None
self._global_plan = None
self._pid_controller = None
self.waypoints_queue = deque(maxlen=20000) # queue with tuples of (waypoint, RoadOption)
self._buffer_size = 5
self._waypoint_buffer = deque(maxlen=self._buffer_size)
self._init_controller() # initializing controller
def reset_vehicle(self):
"""Reset the ego-vehicle"""
self._vehicle = None
print("Resetting ego-vehicle!")
def _init_controller(self):
"""
Controller initialization.
dt -- time difference between physics control in seconds.
This is can be fixed from server side
using the arguments -benchmark -fps=F, since dt = 1/F
target_speed -- desired cruise speed in km/h
min_distance -- minimum distance to remove waypoint from queue
lateral_dict -- dictionary of arguments to setup the lateral PID controller
{'K_P':, 'K_D':, 'K_I':, 'dt'}
longitudinal_dict -- dictionary of arguments to setup the longitudinal PID controller
{'K_P':, 'K_D':, 'K_I':, 'dt'}
"""
# Default parameters
self.args_lat_hw_dict = {
'K_P': 0.75,
'K_D': 0.02,
'K_I': 0.4,
'dt': 1.0 / self.FPS}
self.args_lat_city_dict = {
'K_P': 0.58,
'K_D': 0.02,
'K_I': 0.5,
'dt': 1.0 / self.FPS}
self.args_long_hw_dict = {
'K_P': 0.37,
'K_D': 0.024,
'K_I': 0.032,
'dt': 1.0 / self.FPS}
self.args_long_city_dict = {
'K_P': 0.15,
'K_D': 0.05,
'K_I': 0.07,
'dt': 1.0 / self.FPS}
self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
self._global_plan = False
self._target_speed = self._vehicle.get_speed_limit()
self._min_distance = 3
def set_speed(self, speed):
"""
Request new target speed.
:param speed: new target speed in km/h
"""
self._target_speed = speed
def set_global_plan(self, current_plan, clean=False):
"""
Sets new global plan.
:param current_plan: list of waypoints in the actual plan
"""
for elem in current_plan:
self.waypoints_queue.append(elem)
if clean:
self._waypoint_buffer.clear()
for _ in range(self._buffer_size):
if self.waypoints_queue:
self._waypoint_buffer.append(
self.waypoints_queue.popleft())
else:
break
self._global_plan = True
def get_incoming_waypoint_and_direction(self, steps=3):
"""
Returns direction and waypoint at a distance ahead defined by the user.
:param steps: number of steps to get the incoming waypoint.
"""
if len(self.waypoints_queue) > steps:
return self.waypoints_queue[steps]
else:
try:
wpt, direction = self.waypoints_queue[-1]
return wpt, direction
except IndexError as i:
print(i)
return None, RoadOption.VOID
return None, RoadOption.VOID
def run_step(self, target_speed=None, debug=False):
"""
Execute one step of local planning which involves
running the longitudinal and lateral PID controllers to
follow the waypoints trajectory.
:param target_speed: desired speed
:param debug: boolean flag to activate waypoints debugging
:return: control
"""
if target_speed is not None:
self._target_speed = target_speed
else:
self._target_speed = self._vehicle.get_speed_limit()
if len(self.waypoints_queue) == 0:
control = carla.VehicleControl()
control.steer = 0.0
control.throttle = 0.0
control.brake = 1.0
control.hand_brake = False
control.manual_gear_shift = False
return control
# Buffering the waypoints
if not self._waypoint_buffer:
for i in range(self._buffer_size):
if self.waypoints_queue:
self._waypoint_buffer.append(
self.waypoints_queue.popleft())
else:
break
# Current vehicle waypoint
self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location())
# Target waypoint
self.target_waypoint, self.target_road_option = self._waypoint_buffer[0]
if target_speed > 50:
args_lat = self.args_lat_hw_dict
args_long = self.args_long_hw_dict
else:
args_lat = self.args_lat_city_dict
args_long = self.args_long_city_dict
self._pid_controller = VehiclePIDController(self._vehicle,
args_lateral=args_lat,
args_longitudinal=args_long)
control = self._pid_controller.run_step(self._target_speed, self.target_waypoint)
# Purge the queue of obsolete waypoints
vehicle_transform = self._vehicle.get_transform()
max_index = -1
for i, (waypoint, _) in enumerate(self._waypoint_buffer):
if distance_vehicle(
waypoint, vehicle_transform) < self._min_distance:
max_index = i
if max_index >= 0:
for i in range(max_index + 1):
self._waypoint_buffer.popleft()
if debug:
draw_waypoints(self._vehicle.get_world(),
[self.target_waypoint], 1.0)
return control
================================================
FILE: agents/navigation/roaming_agent.py
================================================
#!/usr/bin/env python
# Copyright (c) 2018 Intel Labs.
# authors: German Ros (german.ros@intel.com)
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module implements an agent that roams around a track following random waypoints and avoiding other vehicles.
The agent also responds to traffic lights. """
from agents.navigation.agent import Agent, AgentState
from agents.navigation.local_planner import LocalPlanner
class RoamingAgent(Agent):
"""
RoamingAgent implements a basic agent that navigates scenes making random
choices when facing an intersection.
This agent respects traffic lights and other vehicles.
"""
def __init__(self, vehicle):
"""
:param vehicle: actor to apply to local planner logic onto
"""
super(RoamingAgent, self).__init__(vehicle)
self._proximity_threshold = 10.0 # meters
self._state = AgentState.NAVIGATING
self._local_planner = LocalPlanner(self._vehicle)
def run_step(self, debug=False):
"""
Execute one step of navigation.
:return: carla.VehicleControl
"""
# is there an obstacle in front of us?
hazard_detected = False
# retrieve relevant elements for safe navigation, i.e.: traffic lights
# and other vehicles
actor_list = self._world.get_actors()
vehicle_list = actor_list.filter("*vehicle*")
lights_list = actor_list.filter("*traffic_light*")
# check possible obstacles
vehicle_state, vehicle = self._is_vehicle_hazard(vehicle_list)
if vehicle_state:
if debug:
print('!!! VEHICLE BLOCKING AHEAD [{}])'.format(vehicle.id))
self._state = AgentState.BLOCKED_BY_VEHICLE
hazard_detected = True
# check for the state of the traffic lights
light_state, traffic_light = self._is_light_red(lights_list)
if light_state:
if debug:
print('=== RED LIGHT AHEAD [{}])'.format(traffic_light.id))
self._state = AgentState.BLOCKED_RED_LIGHT
hazard_detected = True
if hazard_detected:
control = self.emergency_stop()
else:
self._state = AgentState.NAVIGATING
# standard local planner behavior
control = self._local_planner.run_step()
return control
================================================
FILE: agents/navigation/types_behavior.py
================================================
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" This module contains the different parameters sets for each behavior. """
class Cautious(object):
"""Class for Cautious agent."""
max_speed = 40
speed_lim_dist = 6
speed_decrease = 12
safety_time = 3
min_proximity_threshold = 12
braking_distance = 6
overtake_counter = -1
tailgate_counter = 0
class Normal(object):
"""Class for Normal agent."""
max_speed = 50
speed_lim_dist = 3
speed_decrease = 10
safety_time = 3
min_proximity_threshold = 10
braking_distance = 5
overtake_counter = 0
tailgate_counter = 0
class Aggressive(object):
"""Class for Aggressive agent."""
max_speed = 70
speed_lim_dist = 1
speed_decrease = 8
safety_time = 3
min_proximity_threshold = 8
braking_distance = 4
overtake_counter = 0
tailgate_counter = -1
================================================
FILE: agents/tools/__init__.py
================================================
================================================
FILE: agents/tools/misc.py
================================================
#!/usr/bin/env python
# Copyright (c) 2018 Intel Labs.
# authors: German Ros (german.ros@intel.com)
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
""" Module with auxiliary functions. """
import math
import numpy as np
import carla
def draw_waypoints(world, waypoints, z=0.5):
"""
Draw a list of waypoints at a certain height given in z.
:param world: carla.world object
:param waypoints: list or iterable container with the waypoints to draw
:param z: height in meters
"""
for wpt in waypoints:
wpt_t = wpt.transform
begin = wpt_t.location + carla.Location(z=z)
angle = math.radians(wpt_t.rotation.yaw)
end = begin + carla.Location(x=math.cos(angle), y=math.sin(angle))
world.debug.draw_arrow(begin, end, arrow_size=0.3, life_time=1.0)
def get_speed(vehicle):
"""
Compute speed of a vehicle in Km/h.
:param vehicle: the vehicle for which speed is calculated
:return: speed as a float in Km/h
"""
vel = vehicle.get_velocity()
return 3.6 * math.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2)
def is_within_distance_ahead(target_transform, current_transform, max_distance):
"""
Check if a target object is within a certain distance in front of a reference object.
:param target_transform: location of the target object
:param current_transform: location of the reference object
:param orientation: orientation of the reference object
:param max_distance: maximum allowed distance
:return: True if target object is within max_distance ahead of the reference object
"""
target_vector = np.array([target_transform.location.x - current_transform.location.x, target_transform.location.y - current_transform.location.y])
norm_target = np.linalg.norm(target_vector)
# If the vector is too short, we can simply stop here
if norm_target < 0.001:
return True
if norm_target > max_distance:
return False
fwd = current_transform.get_forward_vector()
forward_vector = np.array([fwd.x, fwd.y])
d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))
return d_angle < 90.0
def is_within_distance(target_location, current_location, orientation, max_distance, d_angle_th_up, d_angle_th_low=0):
"""
Check if a target object is within a certain distance from a reference object.
A vehicle in front would be something around 0 deg, while one behind around 180 deg.
:param target_location: location of the target object
:param current_location: location of the reference object
:param orientation: orientation of the reference object
:param max_distance: maximum allowed distance
:param d_angle_th_up: upper thereshold for angle
:param d_angle_th_low: low thereshold for angle (optional, default is 0)
:return: True if target object is within max_distance ahead of the reference object
"""
target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y])
norm_target = np.linalg.norm(target_vector)
# If the vector is too short, we can simply stop here
if norm_target < 0.001:
return True
if norm_target > max_distance:
return False
forward_vector = np.array(
[math.cos(math.radians(orientation)), math.sin(math.radians(orientation))])
d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))
return d_angle_th_low < d_angle < d_angle_th_up
def compute_magnitude_angle(target_location, current_location, orientation):
"""
Compute relative angle and distance between a target_location and a current_location
:param target_location: location of the target object
:param current_location: location of the reference object
:param orientation: orientation of the reference object
:return: a tuple composed by the distance to the object and the angle between both objects
"""
target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y])
norm_target = np.linalg.norm(target_vector)
forward_vector = np.array([math.cos(math.radians(orientation)), math.sin(math.radians(orientation))])
d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.)))
return (norm_target, d_angle)
def distance_vehicle(waypoint, vehicle_transform):
"""
Returns the 2D distance from a waypoint to a vehicle
:param waypoint: actual waypoint
:param vehicle_transform: transform of the target vehicle
"""
loc = vehicle_transform.location
x = waypoint.transform.location.x - loc.x
y = waypoint.transform.location.y - loc.y
return math.sqrt(x * x + y * y)
def vector(location_1, location_2):
"""
Returns the unit vector from location_1 to location_2
:param location_1, location_2: carla.Location objects
"""
x = location_2.x - location_1.x
y = location_2.y - location_1.y
z = location_2.z - location_1.z
norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps
return [x / norm, y / norm, z / norm]
def compute_distance(location_1, location_2):
"""
Euclidean distance between 3D points
:param location_1, location_2: 3D points
"""
x = location_2.x - location_1.x
y = location_2.y - location_1.y
z = location_2.z - location_1.z
norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps
return norm
def positive(num):
"""
Return the given number if positive, else 0
:param num: value to check
"""
return num if num > 0.0 else 0.0
================================================
FILE: camera_calibration/README.md
================================================
# Camera Calibration
Under the current setting, all four cameras have **fov 150**. If you want to change their fov, you could use the following code to estimate the corresponding distortion parameters. More discussions here: https://github.com/carla-simulator/carla/issues/3412.
1. Build Carla from source code with commit 0c97e9a5de5b35b759cc5b0955801244ed76791f:
- git clone the latest commit
- git checkout -b branch_id commit_id
- following the guidance in https://carla.readthedocs.io/en/0.9.10/build_linux/
- make launch (so that the Carla is opened with an UE4 editor)
Note that the Carla built from source and its cooresponding environment (Python, environment variables, etc) are only used for estimating the distortion parameters. In all other experiments, we use the official pre-build version 0.9.10.1 and the environment under our setting. If there is any problem during building the Carla, please refer to https://carla.readthedocs.io/en/0.9.10/build_linux/.
2. Conduct Checkboard Calibration
- Download the checkboard asset for Carla Town3
https://github.com/AbanobSoliman/IBISCape and put it in the suggested folder of Carla from source
- In the Carla UE4 editor, click make launch -> Compile -> Build -> Play
- **python collect_data_for_calibration.py** (sensor setting) to collect image for calibration (For more information about the data collecting process, please refer to tutorials about checkboard camera calibration: https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html and the instruction in the original code https://github.com/AbanobSoliman/IBISCape)
- **python calculate_distortion_parameters.py** (line 26-35 to calculate intrinsic matrix, line 32 to select image index for calibration) to output distortion matrix
- Put an image collected by your Carla into this folded and rename it as "test.png".
- **python undistort.py** (line 4-10 to set intrinsics matrix, line 14 to input the distortion matrix from the last step) to verify the effectiveness of the undistortion. Note that the Tangential Distortion effects need extra attention when collect images.
## Images without Distortion
If your application does not involve official benchmarks such town05Long, Longest6 or Leaderboard, you could eliminate all distortions. In [leaderboard/leaderboard/autoagents/agent_wrapper.py](../leaderboard/leaderboard/autoagents/agent_wrapper.py), set all *lens_circle_multiplier* to 0.0, all *lens_circle_falloff* to 5.0, and all *chromatic_aberration_intensity* to 0.0.
Reference: https://carla.readthedocs.io/en/latest/ref_sensors/
## Acknowledgements
The calibration code is based on [IBISCape](https://github.com/AbanobSoliman/IBISCape) and please check out their awsome code.
================================================
FILE: camera_calibration/calculate_distortion_parameters.py
================================================
#!/usr/bin/env python
import cv2
import numpy as np
import os
import glob
# Defining the dimensions of checkerboard
CHECKERBOARD = (7, 7)
criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001)
# Creating vector to store vectors of 3D points for each checkerboard image
objpoints = []
# Creating vector to store vectors of 2D points for each checkerboard image
imgpoints = []
# Defining the world coordinates for 3D points
objp = np.zeros((1, CHECKERBOARD[0] * CHECKERBOARD[1], 3), np.float32)
objp[0,:,:2] = np.mgrid[0:CHECKERBOARD[0], 0:CHECKERBOARD[1]].T.reshape(-1, 2)
prev_img_shape = None
# Extracting path of individual image stored in a given directory
img_path = None
print("Image Path:", img_path, "(Please Change it to your path of Carla **built from source**!!!)")
images = glob.glob(img_path+'/*.png')
ImageSizeX = 1600
ImageSizeY = 900
CameraFOV = 150
f = ImageSizeX /(2 * np.tan(CameraFOV * np.pi / 360))
Cx = ImageSizeX / 2
Cy = ImageSizeY / 2
# intrinsics = np.array([[214.35935394, 0, 800, ],
# [ 0, 214.35935394, 450, ],
# [ 0, 0, 1, ]])
intrinsics = np.array([[f, 0, Cx],
[0, f, Cy],
[0, 0, 1 ]])
print(intrinsics)
for fname in images:
index = int()
if fname[:-4].split("/")[-1][-4:] < "8028" or fname[:-4].split("/")[-1][-4:] > "8068":
continue
img = cv2.imread(fname)
gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY)
# Find the chess board corners
# If desired number of corners are found in the image then ret = true
ret, corners = cv2.findChessboardCorners(gray, CHECKERBOARD, cv2.CALIB_CB_ADAPTIVE_THRESH + cv2.CALIB_CB_NORMALIZE_IMAGE + cv2.CALIB_CB_FAST_CHECK)
"""
If desired number of corner are detected,
we refine the pixel coordinates and display
them on the images of checker board
"""
print(fname, ret)
if ret == True:
objpoints.append(objp)
# refining pixel coordinates for given 2d points.
corners2 = cv2.cornerSubPix(gray, corners, (11,11),(-1,-1), criteria)
imgpoints.append(corners2)
# Draw and display the corners
img = cv2.drawChessboardCorners(img, CHECKERBOARD, corners2, ret)
# cv2.imshow('img',img)
# cv2.waitKey(0)
cv2.destroyAllWindows()
h,w = img.shape[:2]
"""
Performing camera calibration by
passing the value of known 3D points (objpoints)
and corresponding pixel coordinates of the
detected corners (imgpoints)
"""
ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], intrinsics, None, flags=cv2.CALIB_FIX_INTRINSIC+cv2.CALIB_FIX_PRINCIPAL_POINT)
print("Camera matrix : \n")
print(mtx)
print("Distortion Matrix : \n")
print(dist)
print("rvecs : \n")
print(rvecs)
print("tvecs : \n")
print(tvecs)
================================================
FILE: camera_calibration/collect_data_for_calibration.py
================================================
#!/usr/bin/env python
# Copyright (c) 2021 IBISC Laborartory, Pelvoux, France
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
##From https://github.com/AbanobSoliman/IBISCape
import random
import glob
import os
import sys
import csv
####Please Change it to your path of Carla **built from source**
egg_path = None
print("Egg Path:", egg_path, "(Please Change it to your path of Carla **built from source**!!!)")
sys.path.append(glob.glob(egg_path)[0])
import cv2
import carla
from carla import ColorConverter as cc
import argparse
import collections
import datetime
import logging
import math
import random
import re
import weakref
try:
import pygame
from pygame.locals import KMOD_CTRL
from pygame.locals import KMOD_SHIFT
from pygame.locals import K_0
from pygame.locals import K_9
from pygame.locals import K_BACKQUOTE
from pygame.locals import K_BACKSPACE
from pygame.locals import K_COMMA
from pygame.locals import K_DOWN
from pygame.locals import K_ESCAPE
from pygame.locals import K_F1
from pygame.locals import K_LEFT
from pygame.locals import K_PERIOD
from pygame.locals import K_RIGHT
from pygame.locals import K_SLASH
from pygame.locals import K_SPACE
from pygame.locals import K_TAB
from pygame.locals import K_UP
from pygame.locals import K_a
from pygame.locals import K_b
from pygame.locals import K_c
from pygame.locals import K_d
from pygame.locals import K_g
from pygame.locals import K_h
from pygame.locals import K_i
from pygame.locals import K_l
from pygame.locals import K_m
from pygame.locals import K_n
from pygame.locals import K_p
from pygame.locals import K_k
from pygame.locals import K_j
from pygame.locals import K_q
from pygame.locals import K_r
from pygame.locals import K_s
from pygame.locals import K_v
from pygame.locals import K_w
from pygame.locals import K_x
from pygame.locals import K_z
from pygame.locals import K_MINUS
from pygame.locals import K_EQUALS
except ImportError:
raise RuntimeError(
'cannot import pygame, make sure pygame package is installed')
try:
import numpy as np
except ImportError:
raise RuntimeError(
'cannot import numpy, make sure numpy package is installed')
try:
import queue
except ImportError:
import Queue as queue
import time
import subprocess
client = carla.Client('localhost', 2000)
client.set_timeout(20.0)
# ==============================================================================
# -- Creating the World --------------------------------------------------------
# ==============================================================================
global world
global m
world = client.get_world()
m = world.get_map()
self = world
self.recording = False
# ==============================================================================
# -- Output files Handling------------------------------------------------------
# ==============================================================================
try:
parent_dir = os.getcwd()
path1 = os.path.join(parent_dir, "RGBD_Calib_i_%s" % (m.name))
os.mkdir(path1)
path4 = os.path.join(path1, "rgb")
os.mkdir(path4)
path8 = os.path.join(path4, "frames")
os.mkdir(path8)
path12 = os.path.join(path1, "depth")
os.mkdir(path12)
path15 = os.path.join(path12, "frames")
os.mkdir(path15)
path10 = os.path.join(path1, "other_sensors")
os.mkdir(path10)
path11 = os.path.join(path1, "vehicle_gt")
os.mkdir(path11)
except OSError:
print("Creation of the directory %s failed" % path1)
print("Creation of the directory %s failed" % path4)
print("Creation of the directory %s failed" % path8)
print("Creation of the directory %s failed" % path10)
print("Creation of the directory %s failed" % path11)
print("Creation of the directory %s failed" % path12)
print("Creation of the directory %s failed" % path15)
else:
print("Successfully created the directory %s " % path1)
print("Successfully created the directory %s " % path4)
print("Successfully created the directory %s " % path8)
print("Successfully created the directory %s " % path10)
print("Successfully created the directory %s " % path11)
print("Successfully created the directory %s " % path12)
print("Successfully created the directory %s " % path15)
file_rgb = open(os.path.join(path4, 'timestamps.csv'), "a")
file_depth = open(os.path.join(path12, 'timestamps.csv'), "a")
file_groundtruth_sync = open(os.path.join(path11, 'groundtruth_sync.csv'), "a")
file_GNSS = open(os.path.join(path10, 'gnss.csv'), "a")
writer0 = csv.writer(file_rgb, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL)
writer0.writerow(['#timestamp [ns]', 'filename'])
writer8 = csv.writer(file_depth, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL)
writer8.writerow(['#timestamp [ns]', 'filename'])
writer4 = csv.writer(file_groundtruth_sync, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL)
writer4.writerow(['#timestamp [ns]', 'p_RS_R_x_m_', 'p_RS_R_y_m_', 'p_RS_R_z_m_', 'v_RS_R_x_mS__1_', 'v_RS_R_y_mS__1_', 'v_RS_R_z_mS__1_', 'a_RS_S_x_mS__2_', 'a_RS_S_y_mS__2_', 'a_RS_S_z_mS__2_', 'q_RS_w__', 'q_RS_x__', 'q_RS_y__', 'q_RS_z__', 'w_RS_S_x_radS__1_', 'w_RS_S_y_radS__1_', 'w_RS_S_z_radS__1_'])
writer5 = csv.writer(file_GNSS, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL)
writer5.writerow(['#timestamp [ns]', 'latitude', 'longitude', 'altitude'])
# ==============================================================================
# -- GnssSensor ----------------------------------------------------------------
# ==============================================================================
class gnssSensor(object):
def __init__(self, parent_actor):
self.sensor = None
self._parent = parent_actor
self.lat = 0.0
self.lon = 0.0
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.gnss')
bp.set_attribute('noise_alt_bias', '0.0')
bp.set_attribute('noise_lat_bias', '0.0')
bp.set_attribute('noise_lon_bias', '0.0')
bp.set_attribute('noise_alt_stddev', '0.0')
bp.set_attribute('noise_lat_stddev', '0.0')
bp.set_attribute('noise_lon_stddev', '0.0')
bp.set_attribute('noise_seed', '0')
bp.set_attribute('sensor_tick', '0.05')
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(
x=-0.2, y=0, z=2.8), carla.Rotation(pitch=0, roll=0, yaw=0)), attach_to=self._parent, attachment_type=carla.AttachmentType.Rigid)
# We need to pass the lambda a weak reference to self to avoid circular
# reference.
weak_self = weakref.ref(self)
self.sensor.listen(
lambda event: gnssSensor._on_gnss_event(weak_self, event))
@staticmethod
def _on_gnss_event(weak_self, event):
self = weak_self()
if not self:
return
self.lat = event.latitude
self.lon = event.longitude
self.alt = event.altitude
self.tmp = event.timestamp
def destroy(self):
self.sensor.stop()
self.sensor.destroy()
# ==============================================================================
# -- Useful Functions-----------------------------------------------------------
# ==============================================================================
def resize_img(img):
scale_percent = 50 # percent of original size
width = int(img.shape[1] * scale_percent / 100)
height = int(img.shape[0] * scale_percent / 100)
dim = (width, height)
# resize image
resized = cv2.resize(img, dim, interpolation = cv2.INTER_AREA)
return resized
def euler_to_quaternion(yaw, pitch, roll):
qx = np.sin(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) - np.cos(roll/2) * np.sin(pitch/2) * np.sin(yaw/2)
qy = np.cos(roll/2) * np.sin(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.cos(pitch/2) * np.sin(yaw/2)
qz = np.cos(roll/2) * np.cos(pitch/2) * np.sin(yaw/2) - np.sin(roll/2) * np.sin(pitch/2) * np.cos(yaw/2)
qw = np.cos(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.sin(pitch/2) * np.sin(yaw/2)
quat = [qw, qx, qy, qz]
return quat/np.linalg.norm(quat)
def draw_rgb_image(surface, image_rgb):
array = np.frombuffer(image_rgb.raw_data, dtype=np.dtype("uint8"))
array = np.reshape(array, (image_rgb.height, image_rgb.width, 4))
array = array[:, :, :3]
array = array[:, :, ::-1]
image_surface = pygame.surfarray.make_surface(resize_img(array.swapaxes(0, 1)))
# image_surface.set_alpha(100)
surface.blit(image_surface, (0, 0))
def draw_depth_image(surface, image_depth):
array = np.frombuffer(image_depth.raw_data, dtype=np.dtype("uint8"))
array = np.reshape(array, (image_depth.height, image_depth.width, 4))
array = array[:, :, :3]
array = array[:, :, ::-1]
image_surface = pygame.surfarray.make_surface(resize_img(array.swapaxes(0, 1)))
# image_surface.set_alpha(100)
surface.blit(image_surface, (1000, 0))
def get_font():
fonts = [x for x in pygame.font.get_fonts()]
default_font = 'ubuntumono'
font = default_font if default_font in fonts else fonts[0]
font = pygame.font.match_font(font)
return pygame.font.Font(font, 14)
def create_main_actors(start_pose, waypoint):
blueprint_library = world.get_blueprint_library()
vehicle = world.spawn_actor(
blueprint_library.filter('vehicle')[1], start_pose)
vehicle.set_simulate_physics(True)
vehicle.set_transform(waypoint.transform)
bp_rgb = blueprint_library.find('sensor.camera.rgb')
fov = "150.0"
print("Current Fov:", fov, "Please Change it to your deisred fov!")
# Modify the basic attributes of the blueprint
bp_rgb.set_attribute('image_size_x', '1600')
bp_rgb.set_attribute('image_size_y', '900')
bp_rgb.set_attribute('sensor_tick', '0.05')
bp_rgb.set_attribute('bloom_intensity', '0.675')
bp_rgb.set_attribute('fov', fov)
bp_rgb.set_attribute('fstop', '1.4')
bp_rgb.set_attribute('iso', '100.0')
bp_rgb.set_attribute('gamma', '2.2')
bp_rgb.set_attribute('lens_flare_intensity', '0.1')
bp_rgb.set_attribute('shutter_speed', '200.0')
# Modify the lens distortion attributes
bp_rgb.set_attribute('chromatic_aberration_intensity', '0.5')
bp_rgb.set_attribute('chromatic_aberration_offset', '0.0')
bp_rgb.set_attribute('lens_circle_falloff', '3.0')
bp_rgb.set_attribute('lens_circle_multiplier', '3.0')
bp_rgb.set_attribute('lens_k', '-1.0')
bp_rgb.set_attribute('lens_kcube', '0.0')
bp_rgb.set_attribute('lens_x_size', '0.08')
bp_rgb.set_attribute('lens_y_size', '0.08')
camera_rgb = world.spawn_actor(
bp_rgb,
carla.Transform(carla.Location(x=1.3, y=0.0, z=2.5),
carla.Rotation(pitch=0.0, roll=0.0, yaw=0.0)),
attach_to=vehicle, attachment_type=carla.AttachmentType.Rigid)
bp_depth = blueprint_library.find('sensor.camera.depth')
# Modify the basic attributes of the blueprint
bp_depth.set_attribute('image_size_x', '160')
bp_depth.set_attribute('image_size_y', '90')
bp_depth.set_attribute('fov', fov)
bp_depth.set_attribute('sensor_tick', '0.05')
# Modify the lens distortion attributes
bp_depth.set_attribute('lens_circle_falloff', '5.0')
bp_depth.set_attribute('lens_circle_multiplier', '0.0')
bp_depth.set_attribute('lens_k', '-1.0')
bp_depth.set_attribute('lens_kcube', '0.0')
bp_depth.set_attribute('lens_x_size', '0.08')
bp_depth.set_attribute('lens_y_size', '0.08')
camera_depth = world.spawn_actor(
bp_depth,
carla.Transform(carla.Location(x=0.0, y=0.0, z=2.8),
carla.Rotation(pitch=0.0, roll=0.0, yaw=0.0)),
attach_to=vehicle, attachment_type=carla.AttachmentType.Rigid)
Gnss_sensor = gnssSensor(vehicle)
return vehicle, camera_rgb, camera_depth, Gnss_sensor
def get_actor_display_name(actor, truncate=250):
name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:])
return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name
def _RGB_sensor_callback(sensor_data, ts, display):
draw_rgb_image(display, sensor_data)
if self.recording:
sensor_data.save_to_disk('RGBD_Calib_i_%s/rgb/frames/%d.png' % (m.name, ts))
file_rgb.write("%d,%d.png \n" % (ts, ts))
def _DEPTH_sensor_callback(sensor_data, ts, display):
sensor_data.convert(cc.LogarithmicDepth)
draw_depth_image(display, sensor_data)
if self.recording:
sensor_data.save_to_disk('RGBD_Calib_i_%s/depth/frames/%d.png' % (m.name, ts))
file_depth.write("%d,%d.png \n" % (ts, ts))
# ==============================================================================
# -- Sensor Synchronization-----------------------------------------------------
# ==============================================================================
class CarlaSyncMode(object):
"""
Context manager to synchronize output from different sensors. Synchronous
mode is enabled as long as we are inside this context
with CarlaSyncMode(world, sensors) as sync_mode:
while True:
data = sync_mode.tick(timeout=1.0)
"""
def __init__(self, world, *sensors, **kwargs):
self.world = world
self.sensors = sensors
self.frame = None
self.delta_seconds = 1.0 / kwargs.get('fps', 20)
self._queues = []
self._settings = None
def __enter__(self):
self._settings = self.world.get_settings()
self.frame = self.world.apply_settings(carla.WorldSettings(
no_rendering_mode=False,
synchronous_mode=True,
fixed_delta_seconds=self.delta_seconds))
def make_queue(register_event):
q = queue.Queue()
register_event(q.put)
self._queues.append(q)
make_queue(self.world.on_tick)
for sensor in self.sensors:
make_queue(sensor.listen)
return self
def tick(self, timeout):
self.frame = self.world.tick()
data = [self._retrieve_data(q, timeout) for q in self._queues]
assert all(x.frame == self.frame for x in data)
return data
def __exit__(self, *args, **kwargs):
self.world.apply_settings(self._settings)
def _retrieve_data(self, sensor_queue, timeout):
while True:
data = sensor_queue.get(timeout=timeout)
if data.frame == self.frame:
return data
# ==============================================================================
# -- Main Function--------------------------------------------------------------
# ==============================================================================
def main():
actor_list = []
pygame.init()
pygame.display.set_caption(
'IBISCape: Multi-modal Data Acquisition Framework')
display = pygame.display.set_mode(
(1200, 450),
pygame.HWSURFACE | pygame.DOUBLEBUF)
font = get_font()
clock = pygame.time.Clock()
iterator = 1
rvrs = False
hand_brake = False
try:
start_Pose = m.get_spawn_points()
start_pose = start_Pose[32]
waypoint = m.get_waypoint(start_pose.location)
vehicle, camera_rgb, camera_depth, Gnss_sensor = create_main_actors(start_pose, waypoint)
file_veh_sim = open(os.path.join(path11, '%s_simulation.txt' %
get_actor_display_name(vehicle, truncate=200)), "a")
file_associate = open(os.path.join(path11, 'association.txt'),"a")
actor_list.append(vehicle)
actor_list.append(camera_rgb)
actor_list.append(camera_depth)
actor_list.append(Gnss_sensor)
# Create a synchronous mode context.
with CarlaSyncMode(world, camera_rgb, camera_depth, fps=20) as sync_mode:
while True:
for event in pygame.event.get():
if event.type == pygame.QUIT:
pygame.quit()
elif event.type == pygame.KEYDOWN:
if event.key == K_r:
self.recording = not self.recording
elif event.key == K_q:
rvrs = not rvrs
elif event.key == K_SPACE:
vehicle.disable_constant_velocity()
vehicle.apply_control(
carla.VehicleControl(hand_brake=not hand_brake))
elif event.key == K_w:
if rvrs:
vehicle.apply_control(
carla.VehicleControl(reverse=True, brake=0.0))
vehicle.enable_constant_velocity(
carla.Vector3D(-3, 0, 0))
else:
vehicle.apply_control(
carla.VehicleControl(throttle=1.0, brake=0.0))
vehicle.enable_constant_velocity(
carla.Vector3D(3, 0, 0))
elif event.key == K_s:
vehicle.disable_constant_velocity()
vehicle.apply_control(
carla.VehicleControl(throttle=0.0, brake=1.0))
elif event.key == K_a:
vehicle.apply_control(
carla.VehicleControl(steer=-1.0))
elif event.key == K_d:
vehicle.apply_control(
carla.VehicleControl(steer=1.0))
elif event.key == pygame.K_ESCAPE:
return
elif event.type == pygame.KEYUP:
if event.key == K_a:
vehicle.apply_control(
carla.VehicleControl(steer=0.0))
elif event.key == K_d:
vehicle.apply_control(
carla.VehicleControl(steer=0.0))
clock.tick()
# Advance the simulation and wait for the data.
snapshot, image_rgb, image_depth = sync_mode.tick(
timeout=2.0)
Pose = vehicle.get_transform()
Accl = vehicle.get_acceleration()
velo = vehicle.get_velocity()
AngV = vehicle.get_angular_velocity()
Ctrl = vehicle.get_control()
t_world = snapshot.timestamp.elapsed_seconds*(10**9)
fps = round(1.0 / snapshot.timestamp.delta_seconds)
# Draw the display.
_RGB_sensor_callback(image_rgb, t_world, display)
_DEPTH_sensor_callback(image_depth, t_world, display)
if self.recording:
file_GNSS.write("%f,%21.21f,%21.21f,%21.21f \n" % (t_world, Gnss_sensor.lat, Gnss_sensor.lon, Gnss_sensor.alt))
quat = euler_to_quaternion(math.radians(Pose.rotation.yaw), math.radians(Pose.rotation.pitch), math.radians(Pose.rotation.roll))
file_groundtruth_sync.write("%d,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f \n" % (t_world, Pose.location.x, Pose.location.y, Pose.location.z, velo.x, velo.y, velo.z, Accl.x, Accl.y, Accl.z, quat[0], quat[1], quat[2], quat[3], math.radians(AngV.x), math.radians(AngV.y), math.radians(AngV.z)))
file_veh_sim.write("%d,%f,%f,%f \n" % (
t_world, Ctrl.throttle, Ctrl.steer, Ctrl.brake))
file_associate.write("%d rgb/%d.png %d depth/%d.png \n" %(t_world,t_world,t_world,t_world))
display.blit(font.render('Calibration Frame Number: %d' % (
iterator), True, (250, 0, 0)), (50, 208))
iterator += 1
display.blit(
font.render('% 5d FPS (real)' %
clock.get_fps(), True, (250, 0, 0)),
(8, 10))
display.blit(
font.render('% 5d FPS (simulated)' %
fps, True, (250, 0, 0)),
(8, 28))
display.blit(font.render('Recording %s' % (
'On' if self.recording else 'Off - Press R Key to Record'), True, (250, 0, 0)), (50, 46))
display.blit(font.render('GNSS:% 24s' % ('(% 3.8f, % 3.8f, % 3.8f)' % (
Gnss_sensor.lat, Gnss_sensor.lon, Gnss_sensor.alt)), True, (250, 0, 0)), (50, 100))
display.blit(font.render('x=%5.8f,y=%5.8f,z=%5.8f (m)' % (
Pose.location.x, Pose.location.y, Pose.location.z), True, (250, 0, 0)), (50, 118))
display.blit(font.render('vx=%5.8f,vy=%5.8f,vz=%5.8f (m/sec)' % (
velo.x, velo.y, velo.z), True, (250, 0, 0)), (50, 136))
display.blit(font.render('ax=%5.8f,ay=%5.8f,az=%5.8f (m/sec^2)' % (
Accl.x, Accl.y, Accl.z), True, (250, 0, 0)), (50, 154))
display.blit(font.render('roll=%5.8f,pitch=%5.8f,yaw=%5.8f (rad)' % (
math.radians(Pose.rotation.roll), math.radians(Pose.rotation.pitch), math.radians(Pose.rotation.yaw)), True, (250, 0, 0)), (50, 172))
display.blit(font.render('r_d=%5.8f,p_d=%5.8f,y_d=%5.8f (rad/sec)' % (
math.radians(AngV.x), math.radians(AngV.y), math.radians(AngV.z)), True, (250, 0, 0)), (50, 190))
pygame.display.flip()
finally:
print('destroying actors.')
for actor in actor_list:
actor.destroy()
file_rgb.close()
file_depth.close()
file_groundtruth_sync.close()
file_GNSS.close()
file_veh_sim.close()
file_associate.close()
pygame.quit()
print('done.')
if __name__ == '__main__':
try:
main()
except KeyboardInterrupt:
print('\nCancelled by user. Bye!')
================================================
FILE: camera_calibration/undistort.py
================================================
import cv2 as cv
import numpy as np
import torch
ImageSizeX = 1600
ImageSizeY = 900
CameraFOV = 150
f = ImageSizeX /(2 * np.tan(CameraFOV * np.pi / 360))
Cx = ImageSizeX / 2
Cy = ImageSizeY / 2
intrinsics = np.array([[f, 0, Cx],
[0, f, Cy],
[0, 0, 1 ]])
distortion_matrix = np.array([[ 0.00888296, -0.00130899, 0.00012061, -0.00338673, 0.00028834]])
newcameramtx, roi = cv.getOptimalNewCameraMatrix(intrinsics, distortion_matrix, (1600, 900), 1, (1600, 900))
# newcameramtx = np.array([[304.14395142, 0, 788.25758876,],
# [ 0, 221.49429321, 449.78972161,],
# [ 0, 0, 1, ],])
#print(roi, newcameramtx)
original_img = cv.imread("test" + '.png')
mapx, mapy = cv.initUndistortRectifyMap(intrinsics, distortion_matrix, None, newcameramtx, (ImageSizeX, ImageSizeY), 5)
undistorted_img = cv.remap(original_img, mapx, mapy, cv.INTER_LINEAR)
cv.imwrite("undistort.png", undistorted_img)
================================================
FILE: dataset/tools/generate_metadata.py
================================================
import json
import pickle
import os, sys
towns = ["01", "02", "03", "04","05", "06", "07", "10"]
index_per_down = ["val"] + [str(_).zfill(2) for _ in range(0, 11)]
data_folder = "../"
json_path = "../collect_data_json"
## Store the length of each route since we truncate those ones with infraction happening
length_dict = {}
for town_name in towns:
for data_index in index_per_down:
length_dict["town"+town_name+"_"+data_index] = {}
try:
with open(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "r") as f:
records = json.load(f)["_checkpoint"]["records"]
except:
print("No json for", os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), flush=True)
continue
for index, record in enumerate(records):
record = records[index]
route_data_folder = os.path.join(data_folder, "town"+town_name+"_"+data_index, record["meta"]["folder_name"])
measurements_files = os.listdir(os.path.join(route_data_folder, "measurements"))
total_length = len(measurements_files)
if record["scores"]["score_composed"] >= 100:
length_dict["town"+town_name+"_"+data_index][route_data_folder] = total_length
continue
# timeout or blocked, remove the last ones where the vehicle stops
if len(record["infractions"]["route_timeout"]) > 0 or \
len(record["infractions"]["vehicle_blocked"]) > 0:
stop_index = 0
for i in range(total_length-1, 0, -1):
fname = os.path.join(route_data_folder, "measurements", str(i).zfill(4)) + ".json"
with open(fname, 'r') as mf:
speed = json.load(mf)["speed"]
if speed > 0.1:
stop_index = i
break
length_dict["town"+town_name+"_"+data_index][route_data_folder] = min(total_length, stop_index + 5)
# collision or red-light
elif len(record["infractions"]["red_light"]) > 0 or \
len(record["infractions"]["collisions_pedestrian"]) > 0 or \
len(record["infractions"]["collisions_vehicle"]) > 0 or \
len(record["infractions"]["collisions_layout"]) > 0:
length_dict["town"+town_name+"_"+data_index][route_data_folder] = max(0, total_length-10)
print(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "Routes with Jsons Finished", flush=True)
#### Data without any json file
all_town_folder = os.listdir(data_folder)
for town_name in towns:
for data_index in index_per_down:
if "town"+town_name+"_"+data_index in all_town_folder:
all_route_folder = os.listdir(os.path.join(data_folder, "town"+town_name+"_"+data_index))
for route_folder in all_route_folder:
route_data_folder = os.path.join(data_folder, "town"+town_name+"_"+data_index, route_folder)
if route_data_folder in length_dict["town"+town_name+"_"+data_index]:
continue
measurements_files = os.listdir(os.path.join(route_data_folder, "measurements"))
total_length = len(measurements_files)
if total_length > 10:
total_length = total_length - 10
stop_index = 0
for i in range(total_length-1, 0, -1):
fname = os.path.join(route_data_folder, "measurements", str(i).zfill(4)) + ".json"
with open(fname, 'r') as mf:
speed = json.load(mf)["speed"]
if speed > 0.1:
stop_index = i
break
length_dict["town"+town_name+"_"+data_index][route_data_folder] = min(total_length, stop_index + 5)
print(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "Routes without Jsons Finished", flush=True)
print("Town-Name #Route-Per-Town #Frames -------------------")
total_cnt = 0
for town_name in length_dict:
cnt = 0
for number_of_frames_per_route in length_dict[town_name].values():
cnt += number_of_frames_per_route
print(town_name, length_dict[town_name], cnt)
total_cnt += cnt
print("Total Frames:", total_cnt)
with open("../dataset_metadata.pkl", "wb") as f:
pickle.dump(length_dict, f)
print("Dataset metadata pickle saved")
================================================
FILE: dataset/tools/generate_random_routes.py
================================================
import glob
import os
import sys
sys.path.append('../../')
import lxml.etree as ET
import argparse
import random
import time
import carla
from agents.navigation.global_route_planner import GlobalRoutePlanner
from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO
WEATHER_LIST = {'ClearNoon':{'cloudiness': 15.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 0.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'CloudyNoon':{'cloudiness': 80.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 45.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetNoon':{'cloudiness': 20.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 45.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetCloudyNoon':{'cloudiness': 90.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 180.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'SoftRainNoon':{'cloudiness': 90.0,
'precipitation': 15.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 315.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'MidRainyNoon':{'cloudiness': 80.0,
'precipitation': 30.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.40,
'sun_azimuth_angle': 0.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'HardRainNoon':{'cloudiness': 90.0,
'precipitation': 60.0,
'precipitation_deposits': 100.0,
'wind_intensity':1.0,
'sun_azimuth_angle': 90.0,
'sun_altitude_angle': 75.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'ClearSunset':{'cloudiness': 15.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 45.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'CloudySunset':{'cloudiness': 80.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 270.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetSunset':{'cloudiness': 20.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 270.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetCloudySunset':{'cloudiness': 90.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 0.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'MidRainSunset':{'cloudiness': 80.0,
'precipitation': 30.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.40,
'sun_azimuth_angle': 270.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'HardRainSunset':{'cloudiness': 80.0,
'precipitation': 60.0,
'precipitation_deposits': 100.0,
'wind_intensity':1.0,
'sun_azimuth_angle': 0.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'SoftRainSunset':{'cloudiness': 90.0,
'precipitation': 15.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.35,
'sun_azimuth_angle': 270.0,
'sun_altitude_angle': 15.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'ClearNight':{'cloudiness': 15.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity': 0.35,
'sun_azimuth_angle': 0.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'CloudyNight':{'cloudiness': 80.0,
'precipitation': 0.0,
'precipitation_deposits': 0.0,
'wind_intensity': 0.35,
'sun_azimuth_angle': 45.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetNight':{'cloudiness': 20.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity': 0.35,
'sun_azimuth_angle': 225.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'WetCloudyNight':{'cloudiness': 90.0,
'precipitation': 0.0,
'precipitation_deposits': 50.0,
'wind_intensity': 0.35,
'sun_azimuth_angle': 225.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'SoftRainNight':{'cloudiness': 90.0,
'precipitation': 15.0,
'precipitation_deposits': 50.0,
'wind_intensity': 0.35,
'sun_azimuth_angle': 270.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'MidRainyNight':{'cloudiness': 80.0,
'precipitation': 30.0,
'precipitation_deposits': 50.0,
'wind_intensity':0.4,
'sun_azimuth_angle': 225.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
'HardRainNight':{'cloudiness': 90.0,
'precipitation': 60.0,
'precipitation_deposits': 100.0,
'wind_intensity':1,
'sun_azimuth_angle': 225.0,
'sun_altitude_angle': -80.0,
'fog_density': 0.0,
'fog_distance': 0.0,
'fog_falloff': 0.0,
'wetness': 0.0,
},
}
def interpolate_trajectory(world_map, waypoints_trajectory, hop_resolution=1.0):
"""
Given some raw keypoints interpolate a full dense trajectory to be used by the user.
Args:
world: an reference to the CARLA world so we can use the planner
waypoints_trajectory: the current coarse trajectory
hop_resolution: is the resolution, how dense is the provided trajectory going to be made
Return:
route: full interpolated route both in GPS coordinates and also in its original form.
"""
dao = GlobalRoutePlannerDAO(world_map, hop_resolution)
grp = GlobalRoutePlanner(dao)
grp.setup()
# Obtain route plan
route = []
is_junction = False
distance = 0
try:
for i in range(len(waypoints_trajectory) - 1): # Goes until the one before the last.
waypoint = waypoints_trajectory[i]
waypoint_next = waypoints_trajectory[i + 1]
interpolated_trace = grp.trace_route(waypoint, waypoint_next)
for i, wp_tuple in enumerate(interpolated_trace):
route.append(wp_tuple[0].transform)
if i > 0:
distance += wp_tuple[0].transform.location.distance(interpolated_trace[i-1][0].transform.location)
if not is_junction:
is_junction = wp_tuple[0].is_junction
# print (wp_tuple[0].transform.location, wp_tuple[1])
except:
return None, distance, is_junction
return route, distance, is_junction
import subprocess
def kill_carla():
kill_process = subprocess.Popen('killall -9 -r CarlaUE4-Linux', shell=True)
kill_process.wait()
time.sleep(5)
def main():
carla_path = os.environ["CARLA_ROOT"]
cmd = 'DISPLAY= bash ' + os.path.join(carla_path, 'CarlaUE4.sh')+f' -opengl -carla-rpc-port={args.port} -nosound'
server_process = subprocess.Popen(cmd, shell=True, preexec_fn=os.setsid)
time.sleep(10) ## Wait for carla
client = carla.Client('localhost', int(args.port))
client.set_timeout(200.0)
print("find carla!", args, flush=True)
world = client.load_world(args.town)
print ('loaded world')
waypoint_list = world.get_map().generate_waypoints(2.0)
print ('got %d possible waypoint'%len(waypoint_list))
actors = world.get_actors()
traffic_lights_list = actors.filter('*traffic_light')
print ('got %d traffic lights'%len(traffic_lights_list))
max_dist = 300
min_dist = 50
valid_route_list = []
number = 0
distance_list = []
is_junction_list = []
world_map = world.get_map()
root = ET.Element('routes')
while number < args.route_num:
start_wp = random.choice(waypoint_list)
end_wp = random.choice(waypoint_list)
start_wp = world_map.get_waypoint(start_wp.transform.location,project_to_road=True, lane_type=carla.LaneType.Driving)
end_wp = world_map.get_waypoint(end_wp.transform.location,project_to_road=True, lane_type=carla.LaneType.Driving)
if start_wp.transform.location.distance(end_wp.transform.location) < min_dist or start_wp.transform.location.distance(end_wp.transform.location) > max_dist:
continue
wp_list, distance, is_junction = interpolate_trajectory(world_map, [start_wp.transform.location, end_wp.transform.location])
if wp_list is None:
continue
if distance <= min_dist or distance >= max_dist:
continue
distance_list.append(distance)
is_junction_list.append(is_junction)
route = ET.SubElement(root, 'route', id='%d'%number, town=args.town)
# choose a random weather
weather = random.choice(list(WEATHER_LIST.keys()))
route = ET.SubElement(route, 'weather', id=weather, cloudiness='%f'%WEATHER_LIST[weather]['cloudiness'], precipitation='%f'%WEATHER_LIST[weather]['precipitation'], precipitation_deposits='%f'%WEATHER_LIST[weather]['precipitation_deposits'], wind_intensity='%f'%WEATHER_LIST[weather]['wind_intensity'], sun_azimuth_angle='%f'%WEATHER_LIST[weather]['sun_azimuth_angle'], sun_altitude_angle='%f'%WEATHER_LIST[weather]['sun_altitude_angle'], fog_density='%f'%WEATHER_LIST[weather]['fog_density'], fog_distance='%f'%WEATHER_LIST[weather]['fog_distance'], fog_falloff='%f'%WEATHER_LIST[weather]['fog_falloff'],wetness='%f'%WEATHER_LIST[weather]['wetness'])
x, y, yaw = start_wp.transform.location.x, start_wp.transform.location.y, start_wp.transform.rotation.yaw
ET.SubElement(route, 'waypoint', x='%f'%x, y='%f'%y, z='0.0',
pitch='0.0', roll='0.0', yaw='%f'%yaw)
x, y, yaw = end_wp.transform.location.x, end_wp.transform.location.y, end_wp.transform.rotation.yaw
ET.SubElement(route, 'waypoint', x='%f'%x, y='%f'%y, z='0.0',
pitch='0.0', roll='0.0', yaw='%f'%yaw)
number += 1
print(number)
print('Avg distance:', sum(distance_list)/number)
print('Portion of going through junction:', sum(is_junction_list)/number)
tree = ET.ElementTree(root)
if args.save_file is not None:
tree.write(args.save_file, xml_declaration=True, encoding='utf-8', pretty_print=True)
if __name__ == '__main__':
global args
parser = argparse.ArgumentParser()
parser.add_argument('--save_file', type=str, required=False, default="./", help='xml file path to save the route waypoints')
parser.add_argument('--town', type=str, default='Town02', help='town for generating routes')
parser.add_argument('--route_num', type=int, default=300, help='number of routes')
parser.add_argument('--port', type=int, default=20023, help='number of routes')
args = parser.parse_args()
main()
================================================
FILE: docs/DATA_PREP.md
================================================
# Prepare Dataset
## Script to Collect for One Xml File
Due to the huge size of the dataset (189K frames - 8TB, 2M frames - 85TB), we provide the instructations to generate the dataset. If the size is still too large for your device, techniques to reduce the size of files could be explored. We look forward to your contributions:).
Update: If your disk space is limited, you could consider trying the techniques mentioned in the compression section of this awesome repo [carla_garge](https://github.com/autonomousvision/carla_garage/blob/main/docs/engineering.md).
The command to collect data from one .xml file is:
```shell
## In the ThinkTwice/ directory
port_for_carla=22023 ## Change the port for each running script to avoid cofliction
port_for_traffic_manager=22033 ## Change the port for each running script to avoid cofliction
route_file=town05_00
is_resume=False ## If there is the corresponding json file in the folder collect_data_json, you could set it as True to continue after the last finished route.
is_local=True
agent_name=roach_ap_agent_data_collection
scenario_file=all_towns_traffic_scenarios_no256
cuda_device=0
CUDA_VISIBLE_DEVICES=$cuda_device nohup bash ./leaderboard/scripts/collect_data.sh $port_for_carla $port_for_traffic_manager $route_file $is_resume $is_local $agent_name $scenario_file 2>&1 > $route_file.log &
```
or simply:
```shell
CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/collect_data.sh 22023 22033 town05_00 False True roach_ap_agent_data_collection all_towns_traffic_scenarios_no256 2>&1 > town05_00.log &
```
Note that one Carla simulator will be opened by the script and there is no need to open Carla manually. **You should manually kill that Carla to avoid *error: address is used* after the collection is done or reports errors.**
## Collect Whole Dataset
For 189K training data + the rest of open loop valdiation data = 400k frames in TCP, please collect data with .xmls in [leaderboard/data/routes_for_open_loop_training](../leaderboard/data/routes_for_open_loop_training) with suffix *00, 01, 02, val*. During open-looped running, we train on town 01,03, 04, 06 and validate on town 02, 05 as in LAV, Transfuser, TCP.
For 2M frames data, please collect data with all .xmls in [leaderboard/data/routes_for_open_loop_training](../leaderboard/data/routes_for_open_loop_training). During open-looped running, we train on all routes except those with suffix *val*.
## Generate More Routes
If you want to collect more data with random routes, you could use [dataset/tools/generate_random_routes.py](../dataset/tools/generate_random_routes.py)
```shell
CUDA_VISIBLE_DEVICES=0 python generate_random_routes.py --save_file tmp.xml --town Town02 --route_num 5 --port 22023
```
## Generate Metadata for Open-Loop Training
After collecting data by the expert, we filter out those frames where expert made mistakes and then generate the meta information for all routes together:
```shell
#In ThinkTwice/dataset/tools directory
python generate_metadata.py #It could take a day for the 2M frames dataset.
```
## Additional Notes
- We strongly recommnd you **first collecting a small number of data** (for example, one route with ~20 frames) to make sure that the functions of open-loop training and closed-loop evaluation work well (by thorough visualizations and test runs). Otherwise, it could be time-consuming and frustrating to find out that there are some bugs or missing information (for example, we do not use semantic lidar sensor in our code).
- Since we do not use any bounding boxs in our code, **if you would like to add some functions about bounding box, please first make sure that the collected information is correct and enough for your desired usage.** Test runs and visualizations as mentioned in the previous note is strongly recommended.
- There are several coordinate system within the code: Unreal, Roach, Lidar, Camera, GNSS, Control, etc. If you want to modify or add any new component, visualizations to check whether they align with existing ones are strongly recommended
- You could modify [leaderboard/team_code/roach_ap_agent_data_collection.py](../leaderboard/team_code/roach_ap_agent_data_collection.py) to save the information you need for training.
- For the size of images, we collect images at 900x1600 and we downsample them into 448x896 to save GPU memory. Thus, you may change the collected images' resolution (as well as depth and segmentation labels) to save disk space.
- For traffic light segmentation in images, we wrote rules regarding color to generate GT, which might not be accurate. You could consider use the build-in API of Carla to generate the GT.
- To reduce the data collection cost, you could first only collect data from Town01, Town03, Town04, and Town06 for training as in Appendix B Table 1 of [TCP](https://arxiv.org/pdf/2206.08129.pdf) and do not conduct open-loop validation, which could approximately half the needed data. When the model achieves *current_throttle_brake_offset < 0.1* and *longitudinal_offset < 0.2* in training set, it is considered fitting well.
================================================
FILE: docs/EVAL.md
================================================
# Clsoed-Loop Evaluation
To evaluate in the town05long:
```shell
## In the ThinkTwice/ directory
port_for_carla=22023 ## Change the port for each running script to avoid cofliction
port_for_traffic_manager=22033 ## Change the port for each running script to avoid cofliction
team_agent=thinktwice_agent
is_resume=False ## If there is the corresponding json file in the folder closed_loop_eval_log, you could set it as True to continue after the last finished route.
is_local=True
ckpt_and_config_path=open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py
scenario_file=all_towns_traffic_scenarios_no256
cuda_device=0
setting_name=thinktwice_town05long
CUDA_VISIBLE_DEVICES=$cuda_device nohup bash ./leaderboard/scripts/evaluation_town05long.sh $port_for_carla $port_for_traffic_manager $team_agent $is_resume $is_local $ckpt_and_config_path $scenario_file $setting_name 2>&1 > $setting_name.log &
```
or simply:
```shell
## In the ThinkTwice/ directory
CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_town05long.sh 22023 22033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py all_towns_traffic_scenarios_no256 thinktwice_town05long 2>&1 > thinktwice_town05long.log &
```
To evaluate in the longest6, you can simply use:
```shell
## In the ThinkTwice/ directory
CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_longest6.sh 23023 23033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py longest6_eval_scenarios thinktwice_longest6 2>&1 > thinktwice_longest6.log &
```
Note that the evaluation result is in the directory **closed_loop_eval_log/results_$setting_name.json** and the visualizations and recordings for debug (top-down view, front view, and canbus) are in the directory **closed_loop_eval_log/eval_log/$setting_name**.
Warning: The visualizations and recordings could take lots of disk space. Please monitor those folders in the [closed_loop_eval_log/eval_log/](../closed_loop_eval_log/eval_log/) and delete those useless ones in time. You could also modify the **save** function of [leaderboard/team_code/thinktwice_agent.py](../leaderboard/team_code/thinktwice_agent.py) to change the saved information during evaluation.
Update: As kindly reminded by the authors of [carla_garge](https://github.com/autonomousvision/carla_garage) (One awsome repo for e2e ad! Check it out for more detials), we update the implementation of longest6 to align with the one used by [Transfuser](https://github.com/autonomousvision/transfuser/tree/2022/leaderboard). Specifically, they ignore the penalty score of running stop sign and increase the number of agents in the scene.
================================================
FILE: docs/INSTALL.md
================================================
# Installation
Modified from mmdetection3d, BEVFormer, UniAD
**a. Env: Create a conda virtual environment and activate it.**
```shell
conda create -n thinktwice python=3.7 -y ## Must be py3.7 required by Carla 9.10
conda activate thinktwice
```
**b. Torch: Install PyTorch and torchvision following the [official instructions](https://pytorch.org/).**
```shell
conda install pytorch==1.12.1 torchvision==0.13.1 torchaudio==0.12.1 cudatoolkit=11.3 -c pytorch -y
```
**c. GCC: Make sure gcc>=5 in conda env.**
```shell
conda install -c omgarcia gcc-6
conda install libgcc -y
conda install -c conda-forge libcxxabi -y
```
**d. CUDA: Before installing MMCV family, you need to set up the environment variables in ~/.bashrc (for compiling some operators on the gpu).**
```shell
export CUDA_HOME=YOUR_CUDA_PATH/
# Eg: export CUDA_HOME=/mnt/cuda-11.3/
export PATH=$PATH:YOUR_CUDA_PATH//bin
# Eg: export CUDA_HOME=/mnt/cuda-11.3/bin
export LD_LIBRARY_PATH=YOUR_CUDA_PATH/lib64:YOUR_CONDA_PATH/envs/thinktwice/lib
# Eg: export LD_LIBRARY_PATH=/mnt/cuda-11.3/lib64:/mnt/miniconda3/envs/thinktwice/lib
export LD_PRELOAD=YOUR_CONDA_PATH/envs/thinktwice/lib/libstdc++.so.6.0.29
# Eg: export LD_PRELOAD=/mnt/miniconda3/envs/thinktwice/lib/libstdc++.so.6.0.29
```
**e. Install mmcv-full, mmdet, and mmseg**
```shell
pip install mmcv-full==1.7.0 -f https://download.openmmlab.com/mmcv/dist/cu113/torch1.12/index.html
pip install mmdet==2.28.2
pip install mmsegmentation==0.30.0
```
**f. Install mmdet3d from source code.**
```shell
git clone https://github.com/open-mmlab/mmdetection3d.git -b 1.0 ## Note that 1.1 is incompatible
cd mmdetection3d
pip install cumm-cu113
pip install spconv-cu113 ## For fast lidar model
MMCV_WITH_OPS=1 FORCE_CUDA=1 pip install -v -e . ## Must have a GPU
```
**g. Other Requirements.**
```shell
conda install -c anaconda protobuf -y
conda install matplotlib -y
conda install requests -y
conda install tabulate -y
conda install protobuf -y
conda install -c anaconda setuptools -y
conda install -c conda-forge libjpeg-turbo -y
conda install -c anaconda decorator -y
conda install shapely -y
conda install -c anaconda ephem -y
conda install -c conda-forge omegaconf -y
conda install -c conda-forge hydra -y
conda install -c anaconda scikit-image -y
conda install -c conda-forge opt_einsum -y
conda install -c conda-forge mpi4py -y
conda install h5py -y
conda install -c conda-forge importlib-metadata -y
conda install -c conda-forge zipp -y
pip install gym==0.17.2
pip install imgaug
pip install opencv-python
pip install opencv-contrib-python
pip install pygame
pip install py_trees==0.8.1
pip install dictor
pip install gym==0.17.2
pip install stable-baselines3==0.8.0
pip install numpy --upgrade
pip install shapely==1.6.4.post2 --force-reinstall ### Important! Higher version of shapely may make the CARLA crash mysteriously!
```
**h. Install Carla. (From Roach)**
```shell
mkdir carla
cd carla
wget https://carla-releases.s3.eu-west-3.amazonaws.com/Linux/CARLA_0.9.10.1.tar.gz
tar -xvzf CARLA_0.9.10.1.tar.gz
echo "export CARLA_ROOT=/mnt/carla" >> /mnt/.bashrc ## Set to your own Carla path and ~/.bashrc in your system
cd Import && wget https://carla-releases.s3.eu-west-3.amazonaws.com/Linux/AdditionalMaps_0.9.10.1.tar.gz
cd .. && bash ImportAssets.sh
rm CARLA_0.9.11.tar.gz Import/AdditionalMaps_0.9.10.1.tar.gz
rm Import/AdditionalMaps_0.9.10.1.tar.gz Import/AdditionalMaps_0.9.11.tar.gz
cd && source .bashrc
echo "$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.10-py3.7-linux-x86_64.egg" >> YOUR_CONDA_PATH/envs/thinktwice/lib/python3.7/site-packages/carla.pth
```
**i. Clone ThinkTwice.**
```shell
git clone git@github.com:OpenDriveLab/ThinkTwice.git
cd ThinkTwice/open_loop_training
python setup.py develop ## Compile CUDA function for LSS from BEVDepth
```
================================================
FILE: docs/TRAIN.md
================================================
# Train Your Model
## Script For Training
Our training pipeline is based on [mmcv](https://github.com/open-mmlab/mmcv) and [mmdet3d](https://github.com/open-mmlab/mmdetection3d). To train a ThinkTwice model, you could use:
```shell
#In ThinkTwice/open_loop_training/ directory
#We train on 16 A100 for 4 days
CUDA_VISIBLE_DEVICES=0,1,2,3,4,5,6,7, python -m torch.distributed.launch --nproc_per_node=8 --master_port=22023 train.py configs/thinktwice.py --work-dir=work_dirs/thinktwice --launcher="pytorch"
```
For single GPU debug, you could simply use:
```shell
#In ThinkTwice/open_loop_training/ directory
CUDA_VISIBLE_DEVICES=0 python train.py configs/thinktwice.py --work-dir=work_dirs/debug
```
## Code Structure
We give the structure of the training code. Note that We only introduce those folders/files are commonly used and modified.
ThinkTwice/open_loop_training
├── ckpt # Checkpoints
├── configs # Hyper-Parameter
├── work_dirs # Training Log
├── code # Preprocessing, DataLoader, Model
│ ├── apis # Training pipeline for mmdet3D
│ ├── core # The hooks for mmdet3D
│ ├── datasets # Preprocessing and DataLoader
| | ├── pipelines # Functions of Preprocessing and DataLoader
│ | ├── samplers # For DDP
│ | └── carla_dataset.py # Framework of Preprocessing and DataLoading
│ ├── model_code # Neural Network
| | ├── backbones # Module of Encoder
| | └── dense_heads # Module of Decoder and Loss Functions
│ └── encoder_decoder_framework.py # Entrance of Neural Network
└── train.py # Entrance of Training
## Tips
- Change **is_dev** in [open_loop_training/configs/thinktwice.py](../open_loop_training/configs/thinktwice.py) to True when you develop your model and to False during training
- Set **is_full** in [open_loop_training/configs/thinktwice.py](../open_loop_training/configs/thinktwice.py) to False would only use the same number of data as TCP while to True would use all possible data recorded in **dataset/dataset_metadata.pkl**.
- Your could start with [open_loop_training/code/encoder_decoder_framework.py](../open_loop_training/configs/thinktwice.py) when you want to learn about the neural network and [open_loop_training/code/datasets/carla_dataset.py](../open_loop_training/configs/thinktwice.py) when you want to learn about data.
================================================
FILE: leaderboard/LICENSE
================================================
MIT License
Copyright (c) 2019 CARLA
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
================================================
FILE: leaderboard/README.md
================================================
## Note by ThinkTwice
We have changed/added some log related functions of the leaderboard for easier debug. For example, each simulated route would have a index in its folder name. For all infractions, the location and timestep would be recorded in the json file.
## Original README.md
The main goal of the CARLA Autonomous Driving Leaderboard is to evaluate the driving proficiency of autonomous agents in realistic traffic situations. The leaderboard serves as an open platform for the community to perform fair and reproducible evaluations, simplifying the comparison between different approaches.
Autonomous agents have to drive through a set of predefined routes. For each route, agents are initialized at a starting point and have to drive to a destination point. The agents will be provided with a description of the route. Routes will happen in a variety of areas, including freeways, urban scenes, and residential districts.
Agents will face multiple traffic situations based in the NHTSA typology, such as:
* Lane merging
* Lane changing
* Negotiations at traffic intersections
* Negotiations at roundabouts
* Handling traffic lights and traffic signs
* Coping with pedestrians, cyclists and other elements
The user can change the weather of the simulation, allowing the evaluation of the agent in a variety of weather conditions, including daylight scenes, sunset, rain, fog, and night, among others.
More information can be found [here](https://leaderboard.carla.org/)
================================================
FILE: leaderboard/data/routes_for_evaluation/routes_longest6.xml
================================================
<?xml version='1.0' encoding='UTF-8'?>
<routes><route id="0" town="Town01">
<waypoint pitch="0.0" roll="0.0" x="334.7254638671875" y="288.90679931640625" yaw="89.9791030883789" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="334.7344970703125" y="313.657958984375" yaw="89.9791030883789" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="357.1101379394531" y="330.47332763671875" yaw="0.03531792759895325" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.45916748046875" y="317.3710021972656" yaw="-90.04281616210938" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.43365478515625" y="283.24346923828125" yaw="-90.04281616210938" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.318115234375" y="128.203857421875" yaw="-90.04266357421875" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.2600402832031" y="50.238136291503906" yaw="-90.04265594482422" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.2330017089844" y="13.925765991210938" yaw="-90.04265594482422" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="368.76617431640625" y="-2.1977765560150146" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="308.4601135253906" y="-2.228360176086426" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="207.614501953125" y="-2.279503107070923" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="173.9556427001953" y="-2.296572685241699" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="153.95753479003906" y="14.065252304077148" yaw="89.93091583251953" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="153.9872283935547" y="38.697792053222656" yaw="89.93091583251953" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="109.57969665527344" y="55.16423034667969" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.3765869140625" y="43.30881881713867" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.37274169921875" y="18.01288414001465" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="68.05789947509766" y="-2.3502776622772217" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="14.081366539001465" y="-2.3776514530181885" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.6820547580718994" y="24.343191146850586" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.4851901531219482" y="122.13080596923828" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.1895012855529785" y="269.0069580078125" yaw="89.88465118408203" z="0.0"/>
<weather id="MidRainDawn" cloudiness="80.000000" precipitation="30.000000" precipitation_deposits="50.000000" wind_intensity="0.400000" sun_azimuth_angle="225.000000" sun_altitude_angle="5.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="1" town="Town01">
<waypoint pitch="360.0" roll="0.0" x="315.2674560546875" y="1.7750924825668335" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="334.6253356933594" y="14.335249900817871" yaw="89.9791030883789" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="315.8530578613281" y="55.40555191040039" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="226.33297729492188" y="55.300819396972656" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="173.5809326171875" y="55.239105224609375" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="157.98867797851562" y="39.896236419677734" yaw="269.930908203125" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="141.9262237548828" y="-2.3128161430358887" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="109.39694213867188" y="-2.329313039779663" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.37610626220703" y="40.17418670654297" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.38069152832031" y="70.33818054199219" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.38651275634766" y="108.64129638671875" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.391845703125" y="143.68722534179688" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.39682006835938" y="176.42515563964844" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.4019775390625" y="210.35337829589844" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="88.41710662841797" y="309.8704833984375" yaw="89.99128723144531" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="75.55514526367188" y="326.3004150390625" yaw="180.0352020263672" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="12.632027626037598" y="326.26177978515625" yaw="180.0352020263672" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="1.8649307489395142" y="296.0408020019531" yaw="269.8846435546875" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="1.4228647947311401" y="76.4553451538086" yaw="269.8846435546875" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="1.3183270692825317" y="24.528728485107422" yaw="269.8846435546875" z="0.0"/>
<weather id="CloudyDawn" cloudiness="80.000000" precipitation="0.000000" precipitation_deposits="0.000000" wind_intensity="0.350000" sun_azimuth_angle="315.000000" sun_altitude_angle="5.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="2" town="Town01">
<waypoint pitch="360.0" roll="0.0" x="338.6842956542969" y="176.00216674804688" yaw="269.9790954589844" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="338.6741638183594" y="148.27407836914062" yaw="269.9790954589844" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="338.6495666503906" y="80.78645324707031" yaw="269.9790954589844" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="320.7290344238281" y="55.4112548828125" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="212.8487548828125" y="55.2850456237793" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="173.32044982910156" y="55.238800048828125" yaw="180.06703186035156" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="157.9892120361328" y="40.340248107910156" yaw="269.930908203125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="157.95950317382812" y="15.695076942443848" yaw="269.930908203125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="173.07179260253906" y="1.702979564666748" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="280.5867614746094" y="1.7575045824050903" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="312.7760314941406" y="1.7738289833068848" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="349.441162109375" y="1.7924233675003052" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="380.9141540527344" y="1.8083845376968384" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.23345947265625" y="14.538103103637695" yaw="89.95734405517578" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.3465576171875" y="166.41212463378906" yaw="89.95733642578125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.4117431640625" y="253.89410400390625" yaw="89.95718383789062" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.44500732421875" y="298.43646240234375" yaw="89.95718383789062" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="378.6864318847656" y="326.48663330078125" yaw="180.0353240966797" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="365.12506103515625" y="326.478271484375" yaw="180.0353240966797" z="0.0"/>
<weather id="CloudyMorning" cloudiness="80.000000" precipitation="0.000000" precipitation_deposits="0.000000" wind_intensity="0.350000" sun_azimuth_angle="135.000000" sun_altitude_angle="35.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="3" town="Town01">
<waypoint pitch="360.0" roll="0.0" x="92.41790771484375" y="315.1663513183594" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.41033172607422" y="265.31756591796875" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.40457153320312" y="227.42677307128906" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.40277099609375" y="215.60093688964844" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="219.9288330078125" y="198.97113037109375" yaw="-0.16769057512283325" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="313.20977783203125" y="198.6981201171875" yaw="-0.16769057512283325" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="338.6866455078125" y="182.45599365234375" yaw="269.9790954589844" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="338.6753234863281" y="151.41770935058594" yaw="269.9790954589844" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="320.4845275878906" y="129.55679321289062" yaw="180.18728637695312" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="199.1981658935547" y="129.16030883789062" yaw="180.18728637695312" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="129.8414764404297" y="128.93359375" yaw="180.18728637695312" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="107.4002685546875" y="128.86024475097656" yaw="180.18728637695312" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.38561248779297" y="102.70710754394531" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="92.381103515625" y="73.05748748779297" yaw="269.99127197265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="114.37248992919922" y="59.16984176635742" yaw="0.0670308843255043" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="135.82371520996094" y="59.19493865966797" yaw="0.0670308843255043" z="0.0"/>
<weather id="HardRainNoon" cloudiness="90.000000" precipitation="60.000000" precipitation_deposits="100.000000" wind_intensity="1.000000" sun_azimuth_angle="90.000000" sun_altitude_angle="75.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="4" town="Town01">
<waypoint pitch="0.0" roll="0.0" x="53.05508041381836" y="-2.35788631439209" yaw="-179.970947265625" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.673415422439575" y="28.63454818725586" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.3427786827087402" y="192.8701171875" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.1942241191864014" y="266.6610107421875" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-2.1050660610198975" y="310.9482727050781" yaw="89.88465118408203" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="24.25780487060547" y="330.2689208984375" yaw="0.03519752621650696" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="67.7093276977539" y="330.29559326171875" yaw="0.03519752621650696" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="103.49156951904297" y="330.31756591796875" yaw="0.035137325525283813" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="271.3299560546875" y="330.4205017089844" yaw="0.035137325525283813" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="316.4518127441406" y="330.4482421875" yaw="0.03531792759895325" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="376.9873352050781" y="330.485595703125" yaw="0.03531792759895325" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.4393310546875" y="290.8396301269531" yaw="-90.04281616210938" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.38623046875" y="219.68142700195312" yaw="-90.04266357421875" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="396.3192443847656" y="129.7147979736328" yaw="-90.04266357421875" z="0.0"/>
<weather id="HardRainTwilight" cloudiness="90.000000" precipitation="60.000000" precipitation_deposits="100.000000" wind_intensity="1.000000" sun_azimuth_angle="135.000000" sun_altitude_angle="0.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="5" town="Town01">
<waypoint pitch="360.0" roll="0.0" x="157.9880828857422" y="39.39617156982422" yaw="269.930908203125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="157.96221923828125" y="17.952861785888672" yaw="269.930908203125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="253.0749053955078" y="1.7435522079467773" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="315.1820983886719" y="1.7750492095947266" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="348.85223388671875" y="1.7921247482299805" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="379.3345031738281" y="1.8075834512710571" yaw="0.029052734375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.24493408203125" y="29.937896728515625" yaw="89.95734405517578" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.2692565917969" y="62.618507385253906" yaw="89.95734405517578" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.34820556640625" y="168.6100311279297" yaw="89.95733642578125" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.4200439453125" y="265.0082702636719" yaw="89.95718383789062" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="392.4576721191406" y="315.3871765136719" yaw="89.95718383789062" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="361.8758850097656" y="326.4762878417969" yaw="180.0353240966797" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="299.8201599121094" y="326.4380187988281" yaw="180.0353240966797" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="269.32763671875" y="326.4192810058594" yaw="180.03514099121094" z="0.0"/>
<weather id="HardRainMorning" cloudiness="90.000000" precipitation="60.000000" precipitation_deposits="100.000000" wind_intensity="1.000000" sun_azimuth_angle="180.000000" sun_altitude_angle="35.000000" fog_density="0.000000" fog_distance="0.000000" fog_falloff="0.000000" wetness="0.000000"/></route>
<route id="6" town="Town02">
<waypoint pitch="360.0" roll="0.0" x="132.08555603027344" y="202.2764892578125" yaw="90.16149139404297" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="132.02027893066406" y="225.43690490722656" yaw="90.16149139404297" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="121.13550567626953" y="237.13720703125" yaw="-179.8026885986328" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="89.0135269165039" y="237.02659606933594" yaw="-179.8026885986328" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="57.835628509521484" y="236.91921997070312" yaw="-179.8026885986328" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="45.694637298583984" y="225.14109802246094" yaw="-89.97502136230469" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="45.70420455932617" y="203.19808959960938" yaw="-89.97502136230469" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="57.2266731262207" y="192.1890869140625" yaw="-0.046491142362356186" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="81.93323516845703" y="192.16903686523438" yaw="-0.046491142362356186" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="118.5882339477539" y="192.13929748535156" yaw="-0.046491142362356186" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="146.61520385742188" y="192.11654663085938" yaw="-0.046491142362356186" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="178.01194763183594" y="192.091064453125" yaw="-0.046491142362356186" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="189.54441833496094" y="203.4066619873047" yaw="89.99028778076172" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="189.54843139648438" y="227.1832733154297" yaw="89.99028778076172" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="189.55213928222656" y="249.05113220214844" yaw="89.99028778076172" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="189.55966186523438" y="293.1253967285156" yaw="89.99021911621094" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="173.5743865966797" y="303.01641845703125" yaw="180.0260009765625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="125.07994079589844" y="302.9944152832031" yaw="180.02587890625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="56.60258102416992" y="302.9635009765625" yaw="180.02587890625" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="29.87148666381836" y="302.9514465332031" yaw="180.0257568359375" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="6.721999168395996" y="302.9410400390625" yaw="180.0257568359375" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-3.567107677459717" y="288.9425048828125" yaw="-90.06791687011719" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-3.6103549003601074" y="252.45834350585938" yaw="-90.06791687011719" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-3.6689157485961914" y="203.05552673339844" yaw="-90.06791687011719" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-3.700047016143799" y="176.79234313964844" yaw="-90.06791687011719" z="0.0"/>
<waypoint pitch="0.0" roll="0.0" x="-3.7666711807250977" y="120.58747100830078" yaw="-90.06791687011719" z="0.0"/>
<waypoint pitch="360.0" roll="0.0" x="10.40816593170166" y="109.631515502929
gitextract_y09f2xlv/
├── .github/
│ └── FUNDING.yml
├── .gitignore
├── LICENSE
├── README.md
├── agents/
│ ├── __init__.py
│ ├── navigation/
│ │ ├── __init__.py
│ │ ├── agent.py
│ │ ├── basic_agent.py
│ │ ├── behavior_agent.py
│ │ ├── controller.py
│ │ ├── global_route_planner.py
│ │ ├── global_route_planner_dao.py
│ │ ├── local_planner.py
│ │ ├── local_planner_behavior.py
│ │ ├── roaming_agent.py
│ │ └── types_behavior.py
│ └── tools/
│ ├── __init__.py
│ └── misc.py
├── camera_calibration/
│ ├── README.md
│ ├── calculate_distortion_parameters.py
│ ├── collect_data_for_calibration.py
│ └── undistort.py
├── dataset/
│ └── tools/
│ ├── generate_metadata.py
│ └── generate_random_routes.py
├── docs/
│ ├── DATA_PREP.md
│ ├── EVAL.md
│ ├── INSTALL.md
│ └── TRAIN.md
├── leaderboard/
│ ├── LICENSE
│ ├── README.md
│ ├── data/
│ │ ├── routes_for_evaluation/
│ │ │ ├── routes_longest6.xml
│ │ │ └── routes_town05_long.xml
│ │ ├── routes_for_open_loop_training/
│ │ │ ├── routes_town01_00.xml
│ │ │ ├── routes_town01_01.xml
│ │ │ ├── routes_town01_02.xml
│ │ │ ├── routes_town01_03.xml
│ │ │ ├── routes_town01_04.xml
│ │ │ ├── routes_town01_05.xml
│ │ │ ├── routes_town01_06.xml
│ │ │ ├── routes_town01_07.xml
│ │ │ ├── routes_town01_08.xml
│ │ │ ├── routes_town01_09.xml
│ │ │ ├── routes_town01_10.xml
│ │ │ ├── routes_town01_11.xml
│ │ │ ├── routes_town01_val.xml
│ │ │ ├── routes_town02_00.xml
│ │ │ ├── routes_town02_01.xml
│ │ │ ├── routes_town02_02.xml
│ │ │ ├── routes_town02_03.xml
│ │ │ ├── routes_town02_04.xml
│ │ │ ├── routes_town02_05.xml
│ │ │ ├── routes_town02_06.xml
│ │ │ ├── routes_town02_07.xml
│ │ │ ├── routes_town02_08.xml
│ │ │ ├── routes_town02_09.xml
│ │ │ ├── routes_town02_10.xml
│ │ │ ├── routes_town02_11.xml
│ │ │ ├── routes_town02_val.xml
│ │ │ ├── routes_town03_00.xml
│ │ │ ├── routes_town03_01.xml
│ │ │ ├── routes_town03_02.xml
│ │ │ ├── routes_town03_03.xml
│ │ │ ├── routes_town03_04.xml
│ │ │ ├── routes_town03_05.xml
│ │ │ ├── routes_town03_06.xml
│ │ │ ├── routes_town03_07.xml
│ │ │ ├── routes_town03_08.xml
│ │ │ ├── routes_town03_09.xml
│ │ │ ├── routes_town03_10.xml
│ │ │ ├── routes_town03_11.xml
│ │ │ ├── routes_town03_val.xml
│ │ │ ├── routes_town04_00.xml
│ │ │ ├── routes_town04_01.xml
│ │ │ ├── routes_town04_02.xml
│ │ │ ├── routes_town04_03.xml
│ │ │ ├── routes_town04_04.xml
│ │ │ ├── routes_town04_05.xml
│ │ │ ├── routes_town04_06.xml
│ │ │ ├── routes_town04_07.xml
│ │ │ ├── routes_town04_08.xml
│ │ │ ├── routes_town04_09.xml
│ │ │ ├── routes_town04_10.xml
│ │ │ ├── routes_town04_11.xml
│ │ │ ├── routes_town04_val.xml
│ │ │ ├── routes_town05_00.xml
│ │ │ ├── routes_town05_01.xml
│ │ │ ├── routes_town05_02.xml
│ │ │ ├── routes_town05_03.xml
│ │ │ ├── routes_town05_04.xml
│ │ │ ├── routes_town05_05.xml
│ │ │ ├── routes_town05_06.xml
│ │ │ ├── routes_town05_07.xml
│ │ │ ├── routes_town05_08.xml
│ │ │ ├── routes_town05_09.xml
│ │ │ ├── routes_town05_10.xml
│ │ │ ├── routes_town05_11.xml
│ │ │ ├── routes_town05_val.xml
│ │ │ ├── routes_town06_00.xml
│ │ │ ├── routes_town06_01.xml
│ │ │ ├── routes_town06_02.xml
│ │ │ ├── routes_town06_03.xml
│ │ │ ├── routes_town06_04.xml
│ │ │ ├── routes_town06_05.xml
│ │ │ ├── routes_town06_06.xml
│ │ │ ├── routes_town06_07.xml
│ │ │ ├── routes_town06_08.xml
│ │ │ ├── routes_town06_09.xml
│ │ │ ├── routes_town06_10.xml
│ │ │ ├── routes_town06_11.xml
│ │ │ ├── routes_town06_val.xml
│ │ │ ├── routes_town07_00.xml
│ │ │ ├── routes_town07_01.xml
│ │ │ ├── routes_town07_02.xml
│ │ │ ├── routes_town07_03.xml
│ │ │ ├── routes_town07_04.xml
│ │ │ ├── routes_town07_05.xml
│ │ │ ├── routes_town07_06.xml
│ │ │ ├── routes_town07_07.xml
│ │ │ ├── routes_town07_08.xml
│ │ │ ├── routes_town07_09.xml
│ │ │ ├── routes_town07_10.xml
│ │ │ ├── routes_town07_11.xml
│ │ │ ├── routes_town07_val.xml
│ │ │ ├── routes_town10_00.xml
│ │ │ ├── routes_town10_01.xml
│ │ │ ├── routes_town10_02.xml
│ │ │ ├── routes_town10_03.xml
│ │ │ ├── routes_town10_04.xml
│ │ │ ├── routes_town10_05.xml
│ │ │ ├── routes_town10_06.xml
│ │ │ ├── routes_town10_07.xml
│ │ │ ├── routes_town10_08.xml
│ │ │ ├── routes_town10_09.xml
│ │ │ ├── routes_town10_10.xml
│ │ │ ├── routes_town10_11.xml
│ │ │ └── routes_town10_val.xml
│ │ └── scenarios/
│ │ ├── all_towns_traffic_scenarios_no256.json
│ │ └── longest6_eval_scenarios.json
│ ├── leaderboard/
│ │ ├── __init__.py
│ │ ├── autoagents/
│ │ │ ├── __init__.py
│ │ │ ├── agent_wrapper.py
│ │ │ ├── autonomous_agent.py
│ │ │ ├── dummy_agent.py
│ │ │ ├── human_agent.py
│ │ │ ├── human_agent_config.txt
│ │ │ ├── npc_agent.py
│ │ │ └── ros_agent.py
│ │ ├── envs/
│ │ │ ├── __init__.py
│ │ │ └── sensor_interface.py
│ │ ├── leaderboard_evaluator.py
│ │ ├── scenarios/
│ │ │ ├── __init__.py
│ │ │ ├── background_activity.py
│ │ │ ├── master_scenario.py
│ │ │ ├── route_scenario.py
│ │ │ ├── scenario_manager.py
│ │ │ └── scenarioatomics/
│ │ │ ├── __init__.py
│ │ │ └── atomic_criteria.py
│ │ └── utils/
│ │ ├── __init__.py
│ │ ├── checkpoint_tools.py
│ │ ├── result_writer.py
│ │ ├── route_indexer.py
│ │ ├── route_manipulation.py
│ │ ├── route_parser.py
│ │ └── statistics_manager.py
│ ├── scripts/
│ │ ├── collect_data.sh
│ │ ├── evaluation_longest6.sh
│ │ └── evaluation_town05long.sh
│ └── team_code/
│ ├── auto_pilot.py
│ ├── base_agent.py
│ ├── map_agent.py
│ ├── pid_controller.py
│ ├── planner.py
│ ├── roach_ap_agent_data_collection.py
│ ├── thinktwice_agent.py
│ └── thinktwice_agent_old.py
├── open_loop_training/
│ ├── __init__.py
│ ├── code/
│ │ ├── __init__.py
│ │ ├── apis/
│ │ │ ├── __init__.py
│ │ │ ├── mmdet_train.py
│ │ │ └── train.py
│ │ ├── core/
│ │ │ └── evaluation/
│ │ │ ├── __init__.py
│ │ │ ├── epoch_hook.py
│ │ │ ├── eval_hooks.py
│ │ │ └── eval_tool.py
│ │ ├── datasets/
│ │ │ ├── __init__.py
│ │ │ ├── base_dataset.py
│ │ │ ├── builder.py
│ │ │ ├── carla_dataset.py
│ │ │ ├── pipelines/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── formating.py
│ │ │ │ ├── loading.py
│ │ │ │ └── transform.py
│ │ │ └── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── distributed_sampler.py
│ │ │ ├── group_sampler.py
│ │ │ └── sampler.py
│ │ ├── encoder_decoder_framework.py
│ │ ├── model_code/
│ │ │ ├── backbones/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── lidarnet.py
│ │ │ │ └── lss.py
│ │ │ └── dense_heads/
│ │ │ ├── __init__.py
│ │ │ ├── multi_scale_deformable_attn_function.py
│ │ │ ├── thinktwice_decoder.py
│ │ │ └── utils.py
│ │ └── utils.py
│ ├── configs/
│ │ ├── _base_/
│ │ │ ├── default_runtime.py
│ │ │ └── schedules/
│ │ │ ├── cosine.py
│ │ │ ├── cyclic_20e.py
│ │ │ ├── cyclic_40e.py
│ │ │ ├── mmdet_schedule_1x.py
│ │ │ ├── schedule_2x.py
│ │ │ ├── schedule_3x.py
│ │ │ ├── seg_cosine_150e.py
│ │ │ ├── seg_cosine_200e.py
│ │ │ └── seg_cosine_50e.py
│ │ └── thinktwice.py
│ ├── ops/
│ │ └── voxel_pooling/
│ │ ├── __init__.py
│ │ ├── src/
│ │ │ ├── voxel_pooling_forward.cpp
│ │ │ └── voxel_pooling_forward_cuda.cu
│ │ └── voxel_pooling.py
│ ├── setup.py
│ └── train.py
├── roach/
│ ├── config/
│ │ └── config_agent.yaml
│ ├── criteria/
│ │ ├── blocked.py
│ │ ├── collision.py
│ │ ├── encounter_light.py
│ │ ├── outside_route_lane.py
│ │ ├── route_deviation.py
│ │ ├── run_red_light.py
│ │ └── run_stop_sign.py
│ ├── log/
│ │ └── ckpt_11833344.pth
│ ├── models/
│ │ ├── distributions.py
│ │ ├── ppo.py
│ │ ├── ppo_buffer.py
│ │ ├── ppo_policy.py
│ │ ├── torch_layers.py
│ │ └── torch_util.py
│ ├── obs_manager/
│ │ ├── actor_state/
│ │ │ ├── control.py
│ │ │ ├── route.py
│ │ │ ├── speed.py
│ │ │ └── velocity.py
│ │ └── birdview/
│ │ ├── chauffeurnet.py
│ │ ├── hdmap_generate.py
│ │ └── maps/
│ │ ├── Town01.h5
│ │ ├── Town02.h5
│ │ ├── Town03.h5
│ │ ├── Town04.h5
│ │ ├── Town05.h5
│ │ ├── Town06.h5
│ │ ├── Town07.h5
│ │ └── Town10HD.h5
│ ├── rl_birdview_agent.py
│ └── utils/
│ ├── config_utils.py
│ ├── expert_noiser.py
│ ├── rl_birdview_wrapper.py
│ ├── traffic_light.py
│ ├── transforms.py
│ └── wandb_callback.py
└── scenario_runner/
├── CARLA_VER
├── Dockerfile
├── Docs/
│ ├── CHANGELOG.md
│ ├── CODE_OF_CONDUCT.md
│ ├── CONTRIBUTING.md
│ ├── FAQ.md
│ ├── agent_evaluation.md
│ ├── coding_standard.md
│ ├── creating_new_scenario.md
│ ├── extra.css
│ ├── getting_scenariorunner.md
│ ├── getting_started.md
│ ├── index.md
│ ├── list_of_scenarios.md
│ ├── metrics_module.md
│ ├── openscenario_support.md
│ ├── requirements.txt
│ └── ros_agent.md
├── Jenkinsfile
├── LICENSE
├── README.md
├── manual_control.py
├── metrics_manager.py
├── mkdocs.yml
├── no_rendering_mode.py
├── requirements.txt
├── scenario_runner.py
└── srunner/
├── __init__.py
├── autoagents/
│ ├── __init__.py
│ ├── agent_wrapper.py
│ ├── autonomous_agent.py
│ ├── dummy_agent.py
│ ├── human_agent.py
│ ├── npc_agent.py
│ ├── ros_agent.py
│ └── sensor_interface.py
├── data/
│ ├── all_towns_traffic_scenarios1_3_4.json
│ ├── all_towns_traffic_scenarios1_3_4_8.json
│ ├── no_scenarios.json
│ ├── routes_debug.xml
│ ├── routes_devtest.xml
│ └── routes_training.xml
├── examples/
│ ├── CatalogExample.xosc
│ ├── ChangeLane.xml
│ ├── ChangingWeather.xosc
│ ├── ControlLoss.xml
│ ├── CutIn.xml
│ ├── CyclistCrossing.xosc
│ ├── FollowLeadingVehicle.xml
│ ├── FollowLeadingVehicle.xosc
│ ├── FreeRide.xml
│ ├── LaneChangeSimple.xosc
│ ├── LeadingVehicle.xml
│ ├── NoSignalJunction.xml
│ ├── ObjectCrossing.xml
│ ├── OppositeDirection.xml
│ ├── OscControllerExample.xosc
│ ├── PedestrianCrossingFront.xosc
│ ├── RunningRedLight.xml
│ ├── SignalizedJunctionLeftTurn.xml
│ ├── SignalizedJunctionRightTurn.xml
│ ├── VehicleTurning.xml
│ └── catalogs/
│ ├── ControllerCatalog.xosc
│ ├── EnvironmentCatalog.xosc
│ ├── ManeuverCatalog.xosc
│ ├── MiscObjectCatalog.xosc
│ ├── PedestrianCatalog.xosc
│ └── VehicleCatalog.xosc
├── metrics/
│ ├── data/
│ │ ├── CriteriaFilter_criteria.json
│ │ ├── DistanceBetweenVehicles_criteria.json
│ │ └── DistanceToLaneCenter_criteria.json
│ ├── examples/
│ │ ├── basic_metric.py
│ │ ├── criteria_filter.py
│ │ ├── distance_between_vehicles.py
│ │ └── distance_to_lane_center.py
│ └── tools/
│ ├── metrics_log.py
│ └── metrics_parser.py
├── openscenario/
│ ├── 0.9.x/
│ │ ├── OpenSCENARIO_Catalog.xsd
│ │ ├── OpenSCENARIO_TypeDefs.xsd
│ │ ├── OpenSCENARIO_v0.9.1.xsd
│ │ └── migration0_9_1to1_0.xslt
│ └── OpenSCENARIO.xsd
├── scenarioconfigs/
│ ├── __init__.py
│ ├── openscenario_configuration.py
│ ├── route_scenario_configuration.py
│ └── scenario_configuration.py
├── scenariomanager/
│ ├── __init__.py
│ ├── actorcontrols/
│ │ ├── __init__.py
│ │ ├── actor_control.py
│ │ ├── basic_control.py
│ │ ├── external_control.py
│ │ ├── npc_vehicle_control.py
│ │ ├── pedestrian_control.py
│ │ ├── simple_vehicle_control.py
│ │ └── vehicle_longitudinal_control.py
│ ├── carla_data_provider.py
│ ├── result_writer.py
│ ├── scenario_manager.py
│ ├── scenarioatomics/
│ │ ├── __init__.py
│ │ ├── atomic_behaviors.py
│ │ ├── atomic_criteria.py
│ │ └── atomic_trigger_conditions.py
│ ├── timer.py
│ ├── traffic_events.py
│ ├── watchdog.py
│ └── weather_sim.py
├── scenarios/
│ ├── __init__.py
│ ├── background_activity.py
│ ├── basic_scenario.py
│ ├── change_lane.py
│ ├── control_loss.py
│ ├── cut_in.py
│ ├── follow_leading_vehicle.py
│ ├── freeride.py
│ ├── junction_crossing_route.py
│ ├── maneuver_opposite_direction.py
│ ├── master_scenario.py
│ ├── no_signal_junction_crossing.py
│ ├── object_crash_intersection.py
│ ├── object_crash_vehicle.py
│ ├── open_scenario.py
│ ├── opposite_vehicle_taking_priority.py
│ ├── other_leading_vehicle.py
│ ├── route_scenario.py
│ ├── signalized_junction_left_turn.py
│ └── signalized_junction_right_turn.py
├── tools/
│ ├── __init__.py
│ ├── openscenario_parser.py
│ ├── py_trees_port.py
│ ├── route_manipulation.py
│ ├── route_parser.py
│ ├── scenario_helper.py
│ └── scenario_parser.py
└── utilities/
└── code_check_and_formatting.sh
SYMBOL INDEX (1799 symbols across 153 files)
FILE: agents/navigation/agent.py
class AgentState (line 18) | class AgentState(Enum):
class Agent (line 27) | class Agent(object):
method __init__ (line 30) | def __init__(self, vehicle):
method get_local_planner (line 50) | def get_local_planner(self):
method run_step (line 55) | def run_step(debug=False):
method _is_light_red (line 73) | def _is_light_red(self, lights_list):
method _get_trafficlight_trigger_location (line 110) | def _get_trafficlight_trigger_location(self, traffic_light): # pylint...
method _bh_is_vehicle_hazard (line 133) | def _bh_is_vehicle_hazard(self, ego_wpt, ego_loc, vehicle_list,
method _is_vehicle_hazard (line 189) | def _is_vehicle_hazard(self, vehicle_list):
method emergency_stop (line 222) | def emergency_stop():
FILE: agents/navigation/basic_agent.py
class BasicAgent (line 17) | class BasicAgent(Agent):
method __init__ (line 23) | def __init__(self, vehicle, target_speed=20):
method set_destination (line 47) | def set_destination(self, location):
method _trace_route (line 61) | def _trace_route(self, start_waypoint, end_waypoint):
method run_step (line 81) | def run_step(self, debug=False):
method done (line 123) | def done(self):
FILE: agents/navigation/behavior_agent.py
class BehaviorAgent (line 22) | class BehaviorAgent(Agent):
method __init__ (line 36) | def __init__(self, vehicle, ignore_traffic_light=False, behavior='norm...
method update_information (line 77) | def update_information(self, world):
method set_destination (line 105) | def set_destination(self, start_location, end_location, clean=False):
method reroute (line 123) | def reroute(self, spawn_points):
method _trace_route (line 139) | def _trace_route(self, start_waypoint, end_waypoint):
method traffic_light_manager (line 163) | def traffic_light_manager(self, waypoint):
method _overtake (line 186) | def _overtake(self, location, waypoint, vehicle_list):
method _tailgating (line 219) | def _tailgating(self, location, waypoint, vehicle_list):
method collision_and_car_avoid_manager (line 255) | def collision_and_car_avoid_manager(self, location, waypoint):
method pedestrian_avoid_manager (line 300) | def pedestrian_avoid_manager(self, location, waypoint):
method car_following_manager (line 328) | def car_following_manager(self, vehicle, distance, debug=False):
method run_step (line 360) | def run_step(self, debug=False):
FILE: agents/navigation/controller.py
class VehiclePIDController (line 15) | class VehiclePIDController():
method __init__ (line 23) | def __init__(self, vehicle, args_lateral, args_longitudinal, max_throt...
method run_step (line 50) | def run_step(self, target_speed, waypoint):
class PIDLongitudinalController (line 91) | class PIDLongitudinalController():
method __init__ (line 97) | def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03):
method run_step (line 114) | def run_step(self, target_speed, debug=False):
method _pid_control (line 129) | def _pid_control(self, target_speed, current_speed):
class PIDLateralController (line 150) | class PIDLateralController():
method __init__ (line 155) | def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03):
method run_step (line 172) | def run_step(self, waypoint):
method _pid_control (line 184) | def _pid_control(self, waypoint, vehicle_transform):
FILE: agents/navigation/global_route_planner.py
class GlobalRoutePlanner (line 20) | class GlobalRoutePlanner(object):
method __init__ (line 27) | def __init__(self, dao):
method setup (line 39) | def setup(self):
method _build_graph (line 49) | def _build_graph(self):
method _find_loose_ends (line 108) | def _find_loose_ends(self):
method _localize (line 147) | def _localize(self, location):
method _lane_change_link (line 167) | def _lane_change_link(self):
method _distance_heuristic (line 205) | def _distance_heuristic(self, n1, n2):
method _path_search (line 214) | def _path_search(self, origin, destination):
method _successive_last_intersection_edge (line 232) | def _successive_last_intersection_edge(self, index, route):
method _turn_decision (line 254) | def _turn_decision(self, index, route, threshold=math.radians(35)):
method abstract_route_plan (line 312) | def abstract_route_plan(self, origin, destination):
method _find_closest_in_list (line 332) | def _find_closest_in_list(self, current_waypoint, waypoint_list):
method trace_route (line 344) | def trace_route(self, origin, destination):
FILE: agents/navigation/global_route_planner_dao.py
class GlobalRoutePlannerDAO (line 13) | class GlobalRoutePlannerDAO(object):
method __init__ (line 19) | def __init__(self, wmap, sampling_resolution):
method get_topology (line 29) | def get_topology(self):
method get_waypoint (line 67) | def get_waypoint(self, location):
method get_resolution (line 77) | def get_resolution(self):
FILE: agents/navigation/local_planner.py
class RoadOption (line 17) | class RoadOption(Enum):
class LocalPlanner (line 30) | class LocalPlanner(object):
method __init__ (line 43) | def __init__(self, vehicle, opt_dict=None):
method __del__ (line 81) | def __del__(self):
method reset_vehicle (line 86) | def reset_vehicle(self):
method _init_controller (line 90) | def _init_controller(self, opt_dict):
method set_speed (line 153) | def set_speed(self, speed):
method _compute_next_waypoints (line 162) | def _compute_next_waypoints(self, k=1):
method set_global_plan (line 193) | def set_global_plan(self, current_plan):
method run_step (line 219) | def run_step(self, debug=False):
method done (line 274) | def done(self):
function _retrieve_options (line 282) | def _retrieve_options(list_waypoints, current_waypoint):
function _compute_connection (line 304) | def _compute_connection(current_waypoint, next_waypoint, threshold=35):
FILE: agents/navigation/local_planner_behavior.py
class RoadOption (line 20) | class RoadOption(Enum):
class LocalPlanner (line 34) | class LocalPlanner(object):
method __init__ (line 52) | def __init__(self, agent):
method reset_vehicle (line 76) | def reset_vehicle(self):
method _init_controller (line 81) | def _init_controller(self):
method set_speed (line 129) | def set_speed(self, speed):
method set_global_plan (line 138) | def set_global_plan(self, current_plan, clean=False):
method get_incoming_waypoint_and_direction (line 158) | def get_incoming_waypoint_and_direction(self, steps=3):
method run_step (line 176) | def run_step(self, target_speed=None, debug=False):
FILE: agents/navigation/roaming_agent.py
class RoamingAgent (line 16) | class RoamingAgent(Agent):
method __init__ (line 24) | def __init__(self, vehicle):
method run_step (line 34) | def run_step(self, debug=False):
FILE: agents/navigation/types_behavior.py
class Cautious (line 7) | class Cautious(object):
class Normal (line 19) | class Normal(object):
class Aggressive (line 31) | class Aggressive(object):
FILE: agents/tools/misc.py
function draw_waypoints (line 15) | def draw_waypoints(world, waypoints, z=0.5):
function get_speed (line 31) | def get_speed(vehicle):
function is_within_distance_ahead (line 42) | def is_within_distance_ahead(target_transform, current_transform, max_di...
function is_within_distance (line 68) | def is_within_distance(target_location, current_location, orientation, m...
function compute_magnitude_angle (line 98) | def compute_magnitude_angle(target_location, current_location, orientati...
function distance_vehicle (line 116) | def distance_vehicle(waypoint, vehicle_transform):
function vector (line 130) | def vector(location_1, location_2):
function compute_distance (line 144) | def compute_distance(location_1, location_2):
function positive (line 157) | def positive(num):
FILE: camera_calibration/collect_data_for_calibration.py
class gnssSensor (line 166) | class gnssSensor(object):
method __init__ (line 167) | def __init__(self, parent_actor):
method _on_gnss_event (line 191) | def _on_gnss_event(weak_self, event):
method destroy (line 200) | def destroy(self):
function resize_img (line 208) | def resize_img(img):
function euler_to_quaternion (line 217) | def euler_to_quaternion(yaw, pitch, roll):
function draw_rgb_image (line 226) | def draw_rgb_image(surface, image_rgb):
function draw_depth_image (line 235) | def draw_depth_image(surface, image_depth):
function get_font (line 244) | def get_font():
function create_main_actors (line 252) | def create_main_actors(start_pose, waypoint):
function get_actor_display_name (line 313) | def get_actor_display_name(actor, truncate=250):
function _RGB_sensor_callback (line 318) | def _RGB_sensor_callback(sensor_data, ts, display):
function _DEPTH_sensor_callback (line 324) | def _DEPTH_sensor_callback(sensor_data, ts, display):
class CarlaSyncMode (line 336) | class CarlaSyncMode(object):
method __init__ (line 346) | def __init__(self, world, *sensors, **kwargs):
method __enter__ (line 354) | def __enter__(self):
method tick (line 371) | def tick(self, timeout):
method __exit__ (line 377) | def __exit__(self, *args, **kwargs):
method _retrieve_data (line 380) | def _retrieve_data(self, sensor_queue, timeout):
function main (line 391) | def main():
FILE: dataset/tools/generate_random_routes.py
function interpolate_trajectory (line 254) | def interpolate_trajectory(world_map, waypoints_trajectory, hop_resoluti...
function kill_carla (line 293) | def kill_carla():
function main (line 298) | def main():
FILE: leaderboard/leaderboard/autoagents/agent_wrapper.py
class AgentError (line 40) | class AgentError(Exception):
method __init__ (line 45) | def __init__(self, message):
class AgentWrapper (line 49) | class AgentWrapper(object):
method __init__ (line 72) | def __init__(self, agent):
method __call__ (line 78) | def __call__(self):
method setup_sensors (line 84) | def setup_sensors(self, vehicle, debug_mode=False):
method validate_sensor_configuration (line 221) | def validate_sensor_configuration(sensors, agent_track, selected_track):
method cleanup (line 271) | def cleanup(self):
FILE: leaderboard/leaderboard/autoagents/autonomous_agent.py
class Track (line 21) | class Track(Enum):
class AutonomousAgent (line 29) | class AutonomousAgent(object):
method __init__ (line 35) | def __init__(self, path_to_conf_file):
method setup (line 49) | def setup(self, path_to_conf_file):
method sensors (line 57) | def sensors(self): # pylint: disable=no-self-use
method run_step (line 79) | def run_step(self, input_data, timestamp):
method destroy (line 92) | def destroy(self):
method __call__ (line 99) | def __call__(self):
method set_global_plan (line 120) | def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp...
FILE: leaderboard/leaderboard/autoagents/dummy_agent.py
function get_entry_point (line 16) | def get_entry_point():
class DummyAgent (line 19) | class DummyAgent(AutonomousAgent):
method setup (line 25) | def setup(self, path_to_conf_file):
method sensors (line 31) | def sensors(self):
method run_step (line 68) | def run_step(self, input_data, timestamp):
FILE: leaderboard/leaderboard/autoagents/human_agent.py
function get_entry_point (line 36) | def get_entry_point():
class HumanInterface (line 39) | class HumanInterface(object):
method __init__ (line 45) | def __init__(self):
method run_interface (line 56) | def run_interface(self, input_data):
method _quit (line 70) | def _quit(self):
class HumanAgent (line 74) | class HumanAgent(AutonomousAgent):
method setup (line 83) | def setup(self, path_to_conf_file):
method sensors (line 94) | def sensors(self):
method run_step (line 120) | def run_step(self, input_data, timestamp):
method destroy (line 132) | def destroy(self):
class KeyboardControl (line 139) | class KeyboardControl(object):
method __init__ (line 145) | def __init__(self, path_to_conf_file):
method _json_to_control (line 179) | def _json_to_control(self):
method parse_events (line 192) | def parse_events(self, timestamp):
method _parse_vehicle_keys (line 208) | def _parse_vehicle_keys(self, keys, milliseconds):
method _parse_json_control (line 239) | def _parse_json_control(self):
method _record_control (line 247) | def _record_control(self):
method __del__ (line 262) | def __del__(self):
FILE: leaderboard/leaderboard/autoagents/npc_agent.py
function get_entry_point (line 18) | def get_entry_point():
class NpcAgent (line 21) | class NpcAgent(AutonomousAgent):
method setup (line 30) | def setup(self, path_to_conf_file):
method sensors (line 39) | def sensors(self):
method run_step (line 64) | def run_step(self, input_data, timestamp):
FILE: leaderboard/leaderboard/autoagents/ros_agent.py
class RosAgent (line 40) | class RosAgent(AutonomousAgent):
method setup (line 65) | def setup(self, path_to_conf_file):
method destroy (line 163) | def destroy(self):
method on_vehicle_control (line 184) | def on_vehicle_control(self, data):
method build_camera_info (line 202) | def build_camera_info(self, attributes): # pylint: disable=no-self-use
method publish_plan (line 225) | def publish_plan(self):
method sensors (line 248) | def sensors(self):
method get_header (line 257) | def get_header(self):
method publish_lidar (line 265) | def publish_lidar(self, sensor_id, data):
method publish_gnss (line 286) | def publish_gnss(self, sensor_id, data):
method publish_camera (line 302) | def publish_camera(self, sensor_id, data):
method publish_can (line 316) | def publish_can(self, sensor_id, data):
method publish_hd_map (line 358) | def publish_hd_map(self, sensor_id, data):
method use_stepping_mode (line 403) | def use_stepping_mode(self): # pylint: disable=no-self-use
method run_step (line 409) | def run_step(self, input_data, timestamp):
FILE: leaderboard/leaderboard/envs/sensor_interface.py
function threaded (line 16) | def threaded(fn):
class SensorConfigurationInvalid (line 26) | class SensorConfigurationInvalid(Exception):
method __init__ (line 31) | def __init__(self, message):
class SensorReceivedNoData (line 35) | class SensorReceivedNoData(Exception):
method __init__ (line 40) | def __init__(self, message):
class GenericMeasurement (line 44) | class GenericMeasurement(object):
method __init__ (line 45) | def __init__(self, data, frame):
class BaseReader (line 50) | class BaseReader(object):
method __init__ (line 51) | def __init__(self, vehicle, reading_frequency=1.0):
method __call__ (line 58) | def __call__(self):
method run (line 62) | def run(self):
method listen (line 79) | def listen(self, callback):
method stop (line 83) | def stop(self):
method destroy (line 86) | def destroy(self):
class SpeedometerReader (line 90) | class SpeedometerReader(BaseReader):
method _get_forward_speed (line 96) | def _get_forward_speed(self, transform=None, velocity=None):
method __call__ (line 110) | def __call__(self):
class OpenDriveMapReader (line 128) | class OpenDriveMapReader(BaseReader):
method __call__ (line 129) | def __call__(self):
class CallBack (line 133) | class CallBack(object):
method __init__ (line 134) | def __init__(self, tag, sensor_type, sensor, data_provider):
method __call__ (line 140) | def __call__(self, data):
method _parse_image_cb (line 159) | def _parse_image_cb(self, image, tag):
method _parse_lidar_cb (line 165) | def _parse_lidar_cb(self, lidar_data, tag):
method _parse_semantic_lidar_cb (line 171) | def _parse_semantic_lidar_cb(self, semantic_lidar_data, tag):
method _parse_radar_cb (line 177) | def _parse_radar_cb(self, radar_data, tag):
method _parse_gnss_cb (line 185) | def _parse_gnss_cb(self, gnss_data, tag):
method _parse_imu_cb (line 191) | def _parse_imu_cb(self, imu_data, tag):
method _parse_pseudosensor (line 202) | def _parse_pseudosensor(self, package, tag):
class SensorInterface (line 206) | class SensorInterface(object):
method __init__ (line 207) | def __init__(self):
method register_sensor (line 217) | def register_sensor(self, tag, sensor_type, sensor):
method update_sensor (line 226) | def update_sensor(self, tag, data, timestamp):
method get_data (line 233) | def get_data(self):
FILE: leaderboard/leaderboard/leaderboard_evaluator.py
function str2bool (line 43) | def str2bool(v):
function kill_carla (line 90) | def kill_carla():
class LeaderboardEvaluator (line 95) | class LeaderboardEvaluator(object):
method __init__ (line 108) | def __init__(self, args, statistics_manager):
method _signal_handler (line 157) | def _signal_handler(self, signum, frame):
method __del__ (line 166) | def __del__(self):
method _cleanup (line 177) | def _cleanup(self):
method _prepare_ego_vehicles (line 213) | def _prepare_ego_vehicles(self, ego_vehicles, wait_for_ego_vehicles=Fa...
method _load_and_wait_for_world (line 249) | def _load_and_wait_for_world(self, args, town, ego_vehicles=None):
method _register_statistics (line 295) | def _register_statistics(self, config, checkpoint, entry_status, crash...
method _load_and_run_scenario (line 311) | def _load_and_run_scenario(self, args, config):
method run (line 440) | def run(self, args):
function main (line 479) | def main():
FILE: leaderboard/leaderboard/scenarios/background_activity.py
class BackgroundActivity (line 20) | class BackgroundActivity(BasicScenario):
method __init__ (line 45) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 62) | def _initialize_actors(self, config):
method _create_behavior (line 88) | def _create_behavior(self):
method _create_test_criteria (line 94) | def _create_test_criteria(self):
method __del__ (line 101) | def __del__(self):
FILE: leaderboard/leaderboard/scenarios/master_scenario.py
class MasterScenario (line 28) | class MasterScenario(BasicScenario):
method __init__ (line 40) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _create_behavior (line 59) | def _create_behavior(self):
method _create_test_criteria (line 71) | def _create_test_criteria(self):
method __del__ (line 116) | def __del__(self):
FILE: leaderboard/leaderboard/scenarios/route_scenario.py
function oneshot_behavior (line 70) | def oneshot_behavior(name, variable_name, behaviour):
function convert_json_to_transform (line 103) | def convert_json_to_transform(actor_dict):
function convert_json_to_actor (line 112) | def convert_json_to_actor(actor_dict):
function convert_transform_to_location (line 125) | def convert_transform_to_location(transform_vec):
function compare_scenarios (line 136) | def compare_scenarios(scenario_choice, existent_scenario):
class RouteScenario (line 174) | class RouteScenario(BasicScenario):
method __init__ (line 183) | def __init__(self, world, config, debug_mode=0, criteria_enable=True):
method _update_route (line 212) | def _update_route(self, world, config, debug_mode):
method _update_ego_vehicle (line 244) | def _update_ego_vehicle(self):
method _estimate_route_timeout (line 263) | def _estimate_route_timeout(self):
method _draw_waypoints (line 278) | def _draw_waypoints(self, world, waypoints, vertical_shift, persistenc...
method _scenario_sampling (line 307) | def _scenario_sampling(self, potential_scenarios_definitions, random_s...
method _build_scenario_instances (line 388) | def _build_scenario_instances(self, world, ego_vehicle, scenario_defin...
method _get_actors_instances (line 443) | def _get_actors_instances(self, list_of_antagonist_actors):
method _initialize_actors (line 473) | def _initialize_actors(self, config):
method _create_behavior (line 514) | def _create_behavior(self):
method _create_test_criteria (line 559) | def _create_test_criteria(self):
method __del__ (line 595) | def __del__(self):
FILE: leaderboard/leaderboard/scenarios/scenario_manager.py
class ScenarioManager (line 30) | class ScenarioManager(object):
method __init__ (line 48) | def __init__(self, timeout, debug_mode=False):
method signal_handler (line 82) | def signal_handler(self, signum, frame):
method cleanup (line 88) | def cleanup(self):
method load_scenario (line 99) | def load_scenario(self, scenario, agent, rep_number):
method run_scenario (line 119) | def run_scenario(self):
method _tick_scenario (line 140) | def _tick_scenario(self, timestamp):
method get_running_status (line 185) | def get_running_status(self):
method stop_scenario (line 192) | def stop_scenario(self):
method analyze_scenario (line 214) | def analyze_scenario(self):
FILE: leaderboard/leaderboard/scenarios/scenarioatomics/atomic_criteria.py
class ActorSpeedAboveThresholdTest (line 25) | class ActorSpeedAboveThresholdTest(Criterion):
method __init__ (line 37) | def __init__(self, actor, speed_threshold, below_threshold_max_time,
method update (line 49) | def update(self):
method _set_event_message (line 78) | def _set_event_message(event, location):
method _set_event_dict (line 87) | def _set_event_dict(event, location):
FILE: leaderboard/leaderboard/utils/checkpoint_tools.py
function autodetect_proxy (line 10) | def autodetect_proxy():
function fetch_dict (line 24) | def fetch_dict(endpoint):
function create_default_json_msg (line 50) | def create_default_json_msg():
function save_dict (line 67) | def save_dict(endpoint, data):
FILE: leaderboard/leaderboard/utils/result_writer.py
class ResultOutputProvider (line 19) | class ResultOutputProvider(object):
method __init__ (line 26) | def __init__(self, data, global_result):
method create_output_text (line 41) | def create_output_text(self):
FILE: leaderboard/leaderboard/utils/route_indexer.py
class RouteIndexer (line 13) | class RouteIndexer():
method __init__ (line 14) | def __init__(self, routes_file, scenarios_file, repetitions):
method peek (line 37) | def peek(self):
method next (line 40) | def next(self):
method resume (line 49) | def resume(self, endpoint):
method save_state (line 66) | def save_state(self, endpoint):
FILE: leaderboard/leaderboard/utils/route_manipulation.py
function _location_to_gps (line 21) | def _location_to_gps(lat_ref, lon_ref, location):
function location_route_to_gps (line 44) | def location_route_to_gps(route, lat_ref, lon_ref):
function _get_latlon_ref (line 61) | def _get_latlon_ref(world):
function downsample_route (line 86) | def downsample_route(route, sample_factor):
function interpolate_trajectory (line 132) | def interpolate_trajectory(world, waypoints_trajectory, hop_resolution=1...
FILE: leaderboard/leaderboard/utils/route_parser.py
class RouteParser (line 41) | class RouteParser(object):
method parse_annotations_file (line 48) | def parse_annotations_file(annotation_filename):
method parse_routes_file (line 65) | def parse_routes_file(route_filename, scenario_file, single_route=None):
method parse_weather (line 100) | def parse_weather(route):
method parse_preset_weather (line 140) | def parse_preset_weather(route):
method check_trigger_position (line 154) | def check_trigger_position(new_trigger, existing_triggers):
method convert_waypoint_float (line 176) | def convert_waypoint_float(waypoint):
method match_world_location_to_route (line 186) | def match_world_location_to_route(world_location, route_description):
method get_scenario_type (line 216) | def get_scenario_type(scenario, match_position, trajectory):
method scan_route_for_scenarios (line 297) | def scan_route_for_scenarios(route_name, trajectory, world_annotations):
FILE: leaderboard/leaderboard/utils/statistics_manager.py
class RouteRecord (line 32) | class RouteRecord():
method __init__ (line 33) | def __init__(self):
function to_route_record (line 58) | def to_route_record(record_dict):
function compute_route_length (line 66) | def compute_route_length(config):
class StatisticsManager (line 82) | class StatisticsManager(object):
method __init__ (line 89) | def __init__(self):
method resume (line 93) | def resume(self, endpoint):
method set_route (line 102) | def set_route(self, route_id, index):
method set_scenario (line 115) | def set_scenario(self, scenario):
method compute_route_statistics (line 121) | def compute_route_statistics(self, config, duration_time_system=-1, du...
method compute_global_statistics (line 209) | def compute_global_statistics(self, total_routes):
method save_record (line 243) | def save_record(route_record, index, endpoint):
method save_global_record (line 261) | def save_global_record(route_record, sensors, total_routes, endpoint):
method save_sensors (line 322) | def save_sensors(sensors, endpoint):
method save_entry_status (line 333) | def save_entry_status(entry_status, eligible, endpoint):
method clear_record (line 343) | def clear_record(endpoint):
FILE: leaderboard/team_code/auto_pilot.py
function get_entry_point (line 52) | def get_entry_point():
function _numpy (line 56) | def _numpy(carla_vector, normalize=False):
function _location (line 65) | def _location(x, y, z):
function _orientation (line 69) | def _orientation(yaw):
function get_collision (line 73) | def get_collision(p1, v1, p2, v2):
function check_episode_has_noise (line 86) | def check_episode_has_noise(lat_noise_percent, long_noise_percent):
class AutoPilot (line 98) | class AutoPilot(MapAgent):
method setup (line 105) | def setup(self, path_to_conf_file):
method _init (line 108) | def _init(self):
method _get_angle_to (line 119) | def _get_angle_to(self, pos, theta, target):
method _get_control (line 131) | def _get_control(self, target, far_target, tick_data):
method run_step (line 167) | def run_step(self, input_data, timestamp):
method _should_brake (line 197) | def _should_brake(self):
method _point_inside_boundingbox (line 212) | def _point_inside_boundingbox(self, point, bb_center, bb_extent):
method _get_forward_speed (line 228) | def _get_forward_speed(self, transform=None, velocity=None):
method _is_actor_affected_by_stop (line 242) | def _is_actor_affected_by_stop(self, actor, stop, multi_step=20):
method _is_stop_sign_hazard (line 272) | def _is_stop_sign_hazard(self, stop_sign_list):
method _is_light_red (line 307) | def _is_light_red(self, lights_list):
method _is_walker_hazard (line 317) | def _is_walker_hazard(self, walkers_list):
method _is_vehicle_hazard (line 339) | def _is_vehicle_hazard(self, vehicle_list):
FILE: leaderboard/team_code/base_agent.py
class BaseAgent (line 20) | class BaseAgent(autonomous_agent.AutonomousAgent):
method setup (line 21) | def setup(self, path_to_conf_file):
method _init (line 65) | def _init(self):
method _get_position (line 77) | def _get_position(self, tick_data):
method sensors (line 83) | def sensors(self):
method tick (line 202) | def tick(self, input_data):
method save (line 286) | def save(self, near_node, far_node, near_command, steer, throttle, bra...
method _weather_to_dict (line 346) | def _weather_to_dict(self, carla_weather):
method _create_bb_points (line 362) | def _create_bb_points(self, bb):
method _translate_tl_state (line 380) | def _translate_tl_state(self, state):
method _get_affordances (line 396) | def _get_affordances(self):
method _get_3d_bbs (line 412) | def _get_3d_bbs(self, max_distance=50):
method _get_2d_bbs (line 428) | def _get_2d_bbs(self, seg_cam, affordances, bb_3d, seg_img):
method _draw_2d_bbs (line 493) | def _draw_2d_bbs(self, seg_img, bbs):
method _find_obstacle_3dbb (line 524) | def _find_obstacle_3dbb(self, obstacle_type, max_distance=50):
method _get_2d_bb_baseline (line 571) | def _get_2d_bb_baseline(self, obstacle, distance=2, cam='seg_front'):
method _baseline_to_box (line 602) | def _baseline_to_box(self, baseline, cam, height=1):
method _coords_to_2d_bb (line 620) | def _coords_to_2d_bb(self, cords):
method _change_seg_stop (line 650) | def _change_seg_stop(self, seg_img, depth_img, stop_signs, cam, _regio...
method _trig_to_world (line 701) | def _trig_to_world(self, bb, parent, trigger):
method _create_2d_bb_points (line 719) | def _create_2d_bb_points(self, actor_bb, scale_factor=1):
method _get_sensor_position (line 735) | def _get_sensor_position(self, cam):
method _world_to_sensor (line 748) | def _world_to_sensor(self, cords, sensor, move_cords=False):
method get_matrix (line 775) | def get_matrix(self, transform):
method _change_seg_tl (line 803) | def _change_seg_tl(self, seg_img, depth_img, traffic_lights, _region_s...
method _get_dist (line 830) | def _get_dist(self, p1, p2):
method _get_distance (line 847) | def _get_distance(self, target):
method _get_depth (line 866) | def _get_depth(self, data):
method _find_obstacle (line 884) | def _find_obstacle(self, obstacle_type='*traffic_light*'):
method _get_camera_to_car_calibration (line 924) | def _get_camera_to_car_calibration(self, sensor):
FILE: leaderboard/team_code/map_agent.py
class MapAgent (line 10) | class MapAgent(BaseAgent):
method sensors (line 11) | def sensors(self):
method set_global_plan (line 23) | def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp...
method _init (line 29) | def _init(self):
method tick (line 40) | def tick(self, input_data):
function get_nearby_lights (line 55) | def get_nearby_lights(vehicle, lights, pixels_per_meter=5.5, size=512, r...
function draw_traffic_lights (line 96) | def draw_traffic_lights(image, vehicle, lights, pixels_per_meter=5.5, si...
function draw_stop_signs (line 139) | def draw_stop_signs(image, vehicle, lights, pixels_per_meter=5.5, size=5...
FILE: leaderboard/team_code/pid_controller.py
class PIDController (line 6) | class PIDController(object):
method __init__ (line 7) | def __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20):
method step (line 16) | def step(self, error):
FILE: leaderboard/team_code/planner.py
class Plotter (line 10) | class Plotter(object):
method __init__ (line 11) | def __init__(self, size):
method clear (line 16) | def clear(self):
method dot (line 22) | def dot(self, pos, node, color=(255, 255, 255), r=2):
method show (line 29) | def show(self):
class RoutePlanner (line 39) | class RoutePlanner(object):
method __init__ (line 40) | def __init__(self, min_distance, max_distance, debug_size=256):
method set_route (line 52) | def set_route(self, global_plan, gps=False, global_plan_world = None):
method run_step (line 78) | def run_step(self, gps):
FILE: leaderboard/team_code/roach_ap_agent_data_collection.py
function array_to_bytes (line 30) | def array_to_bytes(x: np.ndarray) -> bytes:
function bytes_to_array (line 35) | def bytes_to_array(b: bytes) -> np.ndarray:
function np_encoder (line 43) | def np_encoder(object):
function get_entry_point (line 52) | def get_entry_point():
function _numpy (line 55) | def _numpy(carla_vector, normalize=False):
function _location (line 62) | def _location(x, y, z):
function get_xyz (line 66) | def get_xyz(_):
function _orientation (line 70) | def _orientation(yaw):
function get_collision (line 74) | def get_collision(p1, v1, p2, v2):
function get_nearby_object (line 85) | def get_nearby_object(vehicle_position, actor_list, radius):
class ROACHAgent (line 94) | class ROACHAgent(autonomous_agent.AutonomousAgent):
method setup (line 95) | def setup(self, path_to_conf_file, ckpt="roach/log/ckpt_11833344.pth"):
method _init (line 164) | def _init(self):
method _get_angle_to (line 193) | def _get_angle_to(self, pos, theta, target):
method _truncate_global_route_till_local_target (line 204) | def _truncate_global_route_till_local_target(self, windows_size=5):
method _get_position (line 221) | def _get_position(self, tick_data):
method set_global_plan (line 226) | def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp...
method sensors (line 237) | def sensors(self):
method tick (line 350) | def tick(self, input_data, timestamp):
method im_render (line 431) | def im_render(self, render_dict):
method run_step (line 447) | def run_step(self, input_data, timestamp):
method collision_detect (line 511) | def collision_detect(self):
method _is_walker_hazard (line 519) | def _is_walker_hazard(self, walkers_list):
method _is_vehicle_hazard (line 536) | def _is_vehicle_hazard(self, vehicle_list):
method save (line 571) | def save(self, near_node, far_node, near_command, far_command, tick_da...
method get_target_gps (line 645) | def get_target_gps(self, gps, compass):
method process_act (line 683) | def process_act(self, action):
method _weather_to_dict (line 699) | def _weather_to_dict(self, carla_weather):
method _get_forward_speed (line 714) | def _get_forward_speed(self, transform=None, velocity=None):
method get_points_in_bbox (line 727) | def get_points_in_bbox(self, ego_mat, vec_inv_mat, dx, lidar):
method _get_3d_bbs (line 738) | def _get_3d_bbs(self, lidar=None, max_distance=50):
method _find_obstacle_3dbb (line 825) | def _find_obstacle_3dbb(self, obstacle_type, max_distance=50):
method get_matrix (line 872) | def get_matrix(self, transform):
FILE: leaderboard/team_code/thinktwice_agent.py
function get_entry_point (line 39) | def get_entry_point():
class GlobalConfig (line 42) | class GlobalConfig:
method __init__ (line 43) | def __init__(self, init_dic):
function obtain_transform_matrix (line 47) | def obtain_transform_matrix(x, y, yaw):
function InverseRotateVector (line 62) | def InverseRotateVector(x, y, yaw):
function obtain_inv_transform_matrix (line 74) | def obtain_inv_transform_matrix(x, y, yaw):
class EgoModel (line 92) | class EgoModel():
method __init__ (line 93) | def __init__(self, dt=1./4):
method forward (line 104) | def forward(self, locs, yaws, spds, acts):
class ThinkTwiceAgent (line 132) | class ThinkTwiceAgent(autonomous_agent.AutonomousAgent):
method setup (line 133) | def setup(self, path_to_conf_file):
method _init (line 219) | def _init(self):
method _get_position (line 226) | def _get_position(self, tick_data):
method sensors (line 231) | def sensors(self):
method tick (line 294) | def tick(self, input_data):
method offset_then_rotate (line 360) | def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ...
method run_step (line 369) | def run_step(self, input_data, timestamp):
method save (line 531) | def save(self, tick_data):
method destroy (line 543) | def destroy(self):
method update_gps_buffer (line 547) | def update_gps_buffer(self, control, theta, speed):
FILE: leaderboard/team_code/thinktwice_agent_old.py
function get_entry_point (line 39) | def get_entry_point():
class GlobalConfig (line 42) | class GlobalConfig:
method __init__ (line 43) | def __init__(self, init_dic):
function obtain_transform_matrix (line 47) | def obtain_transform_matrix(x, y, yaw):
function InverseRotateVector (line 62) | def InverseRotateVector(x, y, yaw):
function obtain_inv_transform_matrix (line 74) | def obtain_inv_transform_matrix(x, y, yaw):
class EgoModel (line 92) | class EgoModel():
method __init__ (line 93) | def __init__(self, dt=1./4):
method forward (line 104) | def forward(self, locs, yaws, spds, acts):
class ThinkTwiceAgent (line 132) | class ThinkTwiceAgent(autonomous_agent.AutonomousAgent):
method setup (line 133) | def setup(self, path_to_conf_file):
method _init (line 219) | def _init(self):
method _get_position (line 226) | def _get_position(self, tick_data):
method sensors (line 231) | def sensors(self):
method tick (line 294) | def tick(self, input_data):
method offset_then_rotate (line 360) | def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ...
method run_step (line 369) | def run_step(self, input_data, timestamp):
method save (line 528) | def save(self, tick_data):
method destroy (line 540) | def destroy(self):
method update_gps_buffer (line 544) | def update_gps_buffer(self, control, theta, speed):
FILE: open_loop_training/code/apis/mmdet_train.py
function custom_train_detector (line 28) | def custom_train_detector(model,
FILE: open_loop_training/code/apis/train.py
function custom_train_model (line 11) | def custom_train_model(model,
function train_model (line 38) | def train_model(model,
FILE: open_loop_training/code/core/evaluation/epoch_hook.py
class MySetEpochInfoHook (line 6) | class MySetEpochInfoHook(Hook):
method before_train_epoch (line 8) | def before_train_epoch(self, runner):
FILE: open_loop_training/code/core/evaluation/eval_hooks.py
function _calc_dynamic_intervals (line 18) | def _calc_dynamic_intervals(start_interval, dynamic_interval_list):
class CustomEvalHook (line 30) | class CustomEvalHook(BaseEvalHook):
method __init__ (line 31) | def __init__(self, *args, dynamic_intervals=None, **kwargs):
method _decide_interval (line 38) | def _decide_interval(self, runner):
method before_train_epoch (line 45) | def before_train_epoch(self, runner):
method before_train_iter (line 50) | def before_train_iter(self, runner):
method _do_evaluate (line 54) | def _do_evaluate(self, runner):
class CustomDistEvalHook (line 91) | class CustomDistEvalHook(BaseDistEvalHook):
method __init__ (line 93) | def __init__(self, *args, dynamic_intervals=None, **kwargs):
method _decide_interval (line 100) | def _decide_interval(self, runner):
method before_train_epoch (line 107) | def before_train_epoch(self, runner):
method before_train_iter (line 112) | def before_train_iter(self, runner):
method _do_evaluate (line 116) | def _do_evaluate(self, runner):
FILE: open_loop_training/code/core/evaluation/eval_tool.py
function custom_encode_mask_results (line 51) | def custom_encode_mask_results(mask_results):
function custom_multi_gpu_test (line 71) | def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=F...
function collect_results_cpu (line 119) | def collect_results_cpu(result_part, size, tmpdir=None):
function collect_results_gpu (line 165) | def collect_results_gpu(result_part, size):
FILE: open_loop_training/code/datasets/base_dataset.py
function expanduser (line 16) | def expanduser(path):
class BaseDataset (line 23) | class BaseDataset(Dataset):
method __init__ (line 37) | def __init__(self,
method load_annotations (line 50) | def load_annotations(self):
method pre_pipeline (line 54) | def pre_pipeline(self, results):
method __len__ (line 60) | def __len__(self):
method __getitem__ (line 63) | def __getitem__(self, idx):
method evaluate (line 69) | def evaluate(self,
FILE: open_loop_training/code/datasets/builder.py
function build_dataloader (line 19) | def build_dataloader(dataset,
function worker_init_fn (line 97) | def worker_init_fn(worker_id, num_workers, rank, seed):
function custom_build_dataset (line 124) | def custom_build_dataset(cfg, default_args=None):
FILE: open_loop_training/code/datasets/carla_dataset.py
class CarlaDataset (line 25) | class CarlaDataset(BaseDataset):
method __init__ (line 28) | def __init__(self,
method load_json (line 92) | def load_json(self, fname):
method load_npy (line 99) | def load_npy(self, fname):
method offset_then_rotate (line 106) | def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ...
method get_data_info (line 115) | def get_data_info(self, data_folder, route_index, is_current):
method prepare_train_data (line 205) | def prepare_train_data(self, index):
method __getitem__ (line 228) | def __getitem__(self, idx):
method _rand_another (line 236) | def _rand_another(self, idx):
method prepare_test_data (line 245) | def prepare_test_data(self, index):
function get_ego_shift (line 252) | def get_ego_shift(delta_x, delta_y, ego_angle):
function union2one (line 263) | def union2one(full_queue_pipeline, queue):
FILE: open_loop_training/code/datasets/pipelines/formating.py
class CarlaFormatBundle (line 15) | class CarlaFormatBundle(object):
method __init__ (line 16) | def __init__(self, ):
method __call__ (line 18) | def __call__(self, results):
method __repr__ (line 28) | def __repr__(self):
class CarlaCollect (line 34) | class CarlaCollect(object):
method __init__ (line 35) | def __init__(self,
method __call__ (line 47) | def __call__(self, results):
method __repr__ (line 70) | def __repr__(self):
FILE: open_loop_training/code/datasets/pipelines/loading.py
class LoadMultiImages (line 27) | class LoadMultiImages(object):
method __init__ (line 28) | def __init__(self,
method load_img (line 40) | def load_img(self, filename):
method __call__ (line 45) | def __call__(self, results):
method __repr__ (line 50) | def __repr__(self):
class LoadPoints (line 58) | class LoadPoints(LoadPointsFromFile):
method __init__ (line 59) | def __init__(self,
method _load_points (line 69) | def _load_points(self, pts_filename):
class LoadDepth (line 77) | class LoadDepth(LoadMultiImages):
method __init__ (line 78) | def __init__(self,
method __call__ (line 84) | def __call__(self, results):
function red_green_yellow (line 96) | def red_green_yellow(rgb_image):
class LoadSeg (line 117) | class LoadSeg(LoadMultiImages):
method __init__ (line 118) | def __init__(self,
method load_img (line 127) | def load_img(self, filename):
method __call__ (line 132) | def __call__(self, results):
FILE: open_loop_training/code/datasets/pipelines/transform.py
class InitMultiImage (line 66) | class InitMultiImage(object):
method __init__ (line 71) | def __init__(self, cfg):
method __call__ (line 95) | def __call__(self, queue):
method __repr__ (line 134) | def __repr__(self):
class ImageTransformMulti (line 142) | class ImageTransformMulti(object):
method __init__ (line 143) | def __init__(self, aug, batch_size):
method __call__ (line 149) | def __call__(self, queue):
method __repr__ (line 166) | def __repr__(self):
function augmenter (line 171) | def augmenter(image_iteration):
class IDAImageTransform (line 222) | class IDAImageTransform(object):
method __init__ (line 223) | def __init__(self, cfg, ida_aug_conf, is_train=False):
method sample_ida_augmentation (line 248) | def sample_ida_augmentation(self):
method __call__ (line 275) | def __call__(self, queue):
function img_transform (line 346) | def img_transform(img, resize, resize_dims, crop, flip, rotate=0):
function get_rot (line 380) | def get_rot(h):
function depth_transform (line 386) | def depth_transform(depth, resize_dims, crop, flip):
FILE: open_loop_training/code/datasets/samplers/distributed_sampler.py
class DistributedSampler (line 9) | class DistributedSampler(_DistributedSampler):
method __init__ (line 11) | def __init__(self,
method __iter__ (line 22) | def __iter__(self):
FILE: open_loop_training/code/datasets/samplers/group_sampler.py
class DistributedGroupSampler (line 14) | class DistributedGroupSampler(Sampler):
method __init__ (line 32) | def __init__(self,
method __iter__ (line 61) | def __iter__(self):
method __len__ (line 101) | def __len__(self):
method set_epoch (line 104) | def set_epoch(self, epoch):
FILE: open_loop_training/code/datasets/samplers/sampler.py
function build_sampler (line 6) | def build_sampler(cfg, default_args):
FILE: open_loop_training/code/encoder_decoder_framework.py
class EncoderDecoder (line 24) | class EncoderDecoder(BaseModule):
method __init__ (line 25) | def __init__(self,
method set_epoch (line 77) | def set_epoch(self, epoch):
method build_fusion_and_flatten_network_for_BEV (line 81) | def build_fusion_and_flatten_network_for_BEV(self):
method train_step (line 140) | def train_step(self, data, optimizer):
method forward_train (line 148) | def forward_train(self, batch):
method forward_inference (line 194) | def forward_inference(self, batch):
method get_fusion_feat (line 213) | def get_fusion_feat(self, cam_feat, lidar_feat,):
method extract_sensor_feat (line 238) | def extract_sensor_feat(self, img, state, img_metas, points, is_train=...
method plot (line 252) | def plot(self, cam_feats, fusion_feats, img_metas):
method process_action (line 268) | def process_action(self, pred, command, speed, target_point):
method _get_action_beta (line 291) | def _get_action_beta(self, alpha, beta):
method control_pid (line 309) | def control_pid(self, waypoints, velocity, target, stuck_desired_speed...
method forward (line 393) | def forward(self, is_eval=True, **kwargs):
method _parse_losses (line 410) | def _parse_losses(self, losses):
method get_downsampled_gt_depth (line 443) | def get_downsampled_gt_depth(self, gt_depths, min_pooling=True):
method get_downsampled_gt_seg (line 485) | def get_downsampled_gt_seg(self, gt_seg):
FILE: open_loop_training/code/model_code/backbones/lidarnet.py
class SparseEncoder_fp32 (line 25) | class SparseEncoder_fp32(SparseEncoder):
method forward (line 28) | def forward(self, voxel_features, coors, batch_size):
class LidarNet (line 62) | class LidarNet(MVXTwoStageDetector):
method __init__ (line 63) | def __init__(self,
method forward (line 87) | def forward(self, pts):
FILE: open_loop_training/code/model_code/backbones/lss.py
class _ASPPModule (line 20) | class _ASPPModule(nn.Module):
method __init__ (line 21) | def __init__(self, inplanes, planes, kernel_size, padding, dilation,
method forward (line 35) | def forward(self, x):
method _init_weight (line 40) | def _init_weight(self):
class ASPP (line 49) | class ASPP(nn.Module):
method __init__ (line 50) | def __init__(self, inplanes, mid_channels=256, BatchNorm=nn.BatchNorm2d):
method forward (line 94) | def forward(self, x):
method _init_weight (line 112) | def _init_weight(self):
class Mlp (line 121) | class Mlp(nn.Module):
method __init__ (line 122) | def __init__(self,
method forward (line 137) | def forward(self, x):
class SELayer (line 146) | class SELayer(nn.Module):
method __init__ (line 147) | def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
method forward (line 154) | def forward(self, x, x_se):
class DepthNet (line 161) | class DepthNet(nn.Module):
method __init__ (line 162) | def __init__(self, in_channels, mid_channels, context_channels,
method forward (line 205) | def forward(self, x, mats_dict): # mats_dict B x T x N
class UnetLayer (line 243) | class UnetLayer(nn.Module):
method __init__ (line 244) | def __init__(self, in_channels, middle_channels, out_channels):
method forward (line 254) | def forward(self, x1, x2):
class UNet (line 260) | class UNet(nn.Module):
method __init__ (line 261) | def __init__(self, n_class, fpn_in_channels):
method forward (line 275) | def forward(self, input):
class PAFPN_fp32 (line 287) | class PAFPN_fp32(PAFPN):
method forward (line 289) | def forward(self, inputs):
class LSS (line 352) | class LSS(BaseModule):
method __init__ (line 353) | def __init__(self, x_bound, y_bound, z_bound, d_bound, final_dim,
method _configure_depth_net (line 443) | def _configure_depth_net(self, depth_net_conf):
method _configure_seg_net (line 451) | def _configure_seg_net(self, seg_net_conf, fpn_in_channels):
method create_frustum (line 454) | def create_frustum(self):
method get_geometry (line 474) | def get_geometry(self, sensor2ego_mat, intrin_mat, ida_mat, bda_mat):
method get_cam_feats (line 515) | def get_cam_feats(self, imgs):
method neck_conv_fp32 (line 530) | def neck_conv_fp32(self, input):
method _forward_depth_net (line 534) | def _forward_depth_net(self, feat, mats_dict):
method _forward_voxel_net (line 538) | def _forward_voxel_net(self, img_feat_with_depth):
method _forward_single_sweep (line 542) | def _forward_single_sweep(self,
method seg_res_to_image_feature_forward (line 625) | def seg_res_to_image_feature_forward(self, input):
method voxel_pooling_method (line 629) | def voxel_pooling_method(self, geom_xyz, img_feat_with_depth, voxel_num):
method forward (line 635) | def forward(self,
FILE: open_loop_training/code/model_code/dense_heads/multi_scale_deformable_attn_function.py
function inverse_sigmoid (line 28) | def inverse_sigmoid(x, eps=1e-5):
class MultiScaleDeformableAttnFunction_fp16 (line 45) | class MultiScaleDeformableAttnFunction_fp16(Function):
method forward (line 49) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,
method backward (line 87) | def backward(ctx, grad_output):
class MultiScaleDeformableAttnFunction_fp32 (line 120) | class MultiScaleDeformableAttnFunction_fp32(Function):
method forward (line 124) | def forward(ctx, value, value_spatial_shapes, value_level_start_index,
method backward (line 163) | def backward(ctx, grad_output):
class PositionwiseFeedForward (line 197) | class PositionwiseFeedForward(nn.Module):
method __init__ (line 199) | def __init__(self, d_in, d_hid, dropout=0.0):
method forward (line 210) | def forward(self, x):
class SpatialCrossAttention (line 216) | class SpatialCrossAttention(BaseModule):
method __init__ (line 229) | def __init__(self,
method init_weight (line 270) | def init_weight(self):
method forward (line 279) | def forward(self,
class MSDeformableAttention3D (line 346) | class MSDeformableAttention3D(BaseModule):
method __init__ (line 371) | def __init__(self,
method init_weights (line 403) | def init_weights(self):
method forward (line 423) | def forward(self,
FILE: open_loop_training/code/model_code/dense_heads/thinktwice_decoder.py
function inv_softplus (line 22) | def inv_softplus(x):
class PredictionModule (line 26) | class PredictionModule(nn.Module):
method __init__ (line 27) | def __init__(self, act):
method forward (line 41) | def forward(self, current_BEV_feature, current_wp, current_ctrl, futur...
class LookModule (line 51) | class LookModule(nn.Module):
method __init__ (line 52) | def __init__(self, act):
method obtain_lidar_look_features (line 79) | def obtain_lidar_look_features(self, wp, lidar_grid):
method obtain_cam_ref_points_query (line 88) | def obtain_cam_ref_points_query(self, reference_points, transform_mat,...
method forward (line 154) | def forward(self, current_wp, current_ctrl_softplus, measurement_feat,...
class ThinkTwiceDecoderLayer (line 189) | class ThinkTwiceDecoderLayer(nn.Module):
method __init__ (line 190) | def __init__(self, act):
method forward (line 236) | def forward(self, BEV_feat, current_wp, current_ctrl, future_bev_feat_...
class ThinkTwiceDecoder (line 263) | class ThinkTwiceDecoder(BaseModule):
method __init__ (line 264) | def __init__(self,
method build_layers (line 292) | def build_layers(self):
method build_coarse_output_layer (line 298) | def build_coarse_output_layer(self):
method build_refine_layers (line 363) | def build_refine_layers(self):
method transform_fpn_feats (line 381) | def transform_fpn_feats(self, mlvl_feats):
method grid2feat (line 405) | def grid2feat(self, grid_feat, parent_module):
method forward (line 419) | def forward(self, flattend_BEV_feat, BEV_feat, measurement_feat, targe...
method loss (line 536) | def loss(self,
method _get_action_beta (line 623) | def _get_action_beta(self, alpha, beta):
FILE: open_loop_training/code/model_code/dense_heads/utils.py
function sigmoid_focal_loss (line 6) | def sigmoid_focal_loss(
function init_weights (line 26) | def init_weights(m):
class SpatialGRU (line 53) | class SpatialGRU(nn.Module):
method __init__ (line 56) | def __init__(self, input_size, hidden_size, act, gru_bias_init=0.0):
method forward (line 82) | def forward(self, x, state=None):
method gru_cell (line 95) | def gru_cell(self, x, state):
FILE: open_loop_training/code/utils.py
class PIDController (line 7) | class PIDController(object):
method __init__ (line 8) | def __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20):
method step (line 17) | def step(self, error):
class FocalLoss (line 31) | class FocalLoss(nn.Module):
method __init__ (line 32) | def __init__(self, alpha=0.5, gamma=2, weight=None, ignore_index=255):
method forward (line 43) | def forward(self, preds, labels):
function set_dropout_zero (line 49) | def set_dropout_zero(m):
function init_weights (line 59) | def init_weights(m):
class SEModule (line 84) | class SEModule(nn.Module):
method __init__ (line 85) | def __init__(self, channels, act):
method forward (line 90) | def forward(self, x):
class SEBasicBlock (line 99) | class SEBasicBlock(nn.Module):
method __init__ (line 100) | def __init__(self, inplanes, act):
method forward (line 110) | def forward(self, x):
FILE: open_loop_training/ops/voxel_pooling/src/voxel_pooling_forward.cpp
function voxel_pooling_forward_wrapper (line 24) | int voxel_pooling_forward_wrapper(int batch_size, int num_points, int nu...
function PYBIND11_MODULE (line 39) | PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
FILE: open_loop_training/ops/voxel_pooling/voxel_pooling.py
class VoxelPooling (line 8) | class VoxelPooling(Function):
method forward (line 10) | def forward(ctx, geom_xyz: torch.Tensor, input_features: torch.Tensor,
method backward (line 58) | def backward(ctx, grad_output_features):
FILE: open_loop_training/setup.py
function make_cuda_ext (line 7) | def make_cuda_ext(name,
FILE: open_loop_training/train.py
function str2bool (line 32) | def str2bool(v):
function parse_args (line 43) | def parse_args():
function main (line 114) | def main():
FILE: roach/criteria/blocked.py
class Blocked (line 4) | class Blocked():
method __init__ (line 6) | def __init__(self, speed_threshold=0.1, below_threshold_max_time=90.0):
method tick (line 11) | def tick(self, vehicle, timestamp):
method _calculate_speed (line 29) | def _calculate_speed(carla_velocity):
FILE: roach/criteria/collision.py
class Collision (line 6) | class Collision():
method __init__ (line 7) | def __init__(self, vehicle, carla_world, intensity_threshold=0.0,
method tick (line 27) | def tick(self, vehicle, timestamp):
method _on_collision (line 50) | def _on_collision(weakself, event):
method clean (line 114) | def clean(self):
FILE: roach/criteria/encounter_light.py
class EncounterLight (line 4) | class EncounterLight():
method __init__ (line 6) | def __init__(self, dist_threshold=7.5):
method tick (line 10) | def tick(self, vehicle, timestamp):
FILE: roach/criteria/outside_route_lane.py
class OutsideRouteLane (line 5) | class OutsideRouteLane():
method __init__ (line 7) | def __init__(self, carla_map, vehicle_loc,
method tick (line 21) | def tick(self, vehicle, timestamp, distance_traveled):
method _is_outside_driving_lanes (line 39) | def _is_outside_driving_lanes(self, location):
method _is_at_wrong_lane (line 62) | def _is_at_wrong_lane(self, location, yaw):
FILE: roach/criteria/route_deviation.py
class RouteDeviation (line 1) | class RouteDeviation():
method __init__ (line 3) | def __init__(self, offroad_min=15, offroad_max=30, max_route_percentag...
method tick (line 9) | def tick(self, vehicle, timestamp, ref_waypoint, distance_traveled, ro...
FILE: roach/criteria/run_red_light.py
class RunRedLight (line 6) | class RunRedLight():
method __init__ (line 8) | def __init__(self, carla_map, distance_light=30):
method tick (line 13) | def tick(self, vehicle, timestamp):
method _is_vehicle_crossing_line (line 57) | def _is_vehicle_crossing_line(seg1, seg2):
FILE: roach/criteria/run_stop_sign.py
class RunStopSign (line 5) | class RunStopSign():
method __init__ (line 7) | def __init__(self, carla_world, proximity_threshold=50.0, speed_thresh...
method tick (line 23) | def tick(self, vehicle, timestamp):
method _scan_for_stop_sign (line 75) | def _scan_for_stop_sign(self, vehicle_transform):
method is_affected_by_stop (line 94) | def is_affected_by_stop(self, vehicle_loc, stop, multi_step=20):
method _calculate_speed (line 127) | def _calculate_speed(carla_velocity):
method point_inside_boundingbox (line 131) | def point_inside_boundingbox(point, bb_center, bb_extent):
FILE: roach/models/distributions.py
function sum_independent_dims (line 9) | def sum_independent_dims(tensor: th.Tensor) -> th.Tensor:
class DiagGaussianDistribution (line 17) | class DiagGaussianDistribution():
method __init__ (line 18) | def __init__(self, action_dim: int, dist_init=None, action_dependent_s...
method proba_distribution_net (line 44) | def proba_distribution_net(self, latent_dim: int) -> Tuple[nn.Module, ...
method proba_distribution (line 66) | def proba_distribution(self, mean_actions: th.Tensor, log_std: th.Tens...
method log_prob (line 73) | def log_prob(self, actions: th.Tensor) -> th.Tensor:
method entropy_loss (line 77) | def entropy_loss(self) -> th.Tensor:
method exploration_loss (line 81) | def exploration_loss(self, exploration_suggests) -> th.Tensor:
method sample (line 100) | def sample(self) -> th.Tensor:
method mode (line 103) | def mode(self) -> th.Tensor:
method get_actions (line 106) | def get_actions(self, deterministic: bool = False) -> th.Tensor:
class SquashedDiagGaussianDistribution (line 112) | class SquashedDiagGaussianDistribution():
method __init__ (line 113) | def __init__(self, action_dim: int, log_std_init: float = 0.0, action_...
method proba_distribution_net (line 128) | def proba_distribution_net(self, latent_dim: int):
method proba_distribution (line 136) | def proba_distribution(self, mean_actions: th.Tensor, log_std: th.Tens...
method log_prob (line 143) | def log_prob(self, actions: th.Tensor, gaussian_actions: Optional[th.T...
method entropy (line 159) | def entropy(self) -> Optional[th.Tensor]:
method sample (line 162) | def sample(self) -> th.Tensor:
method mode (line 165) | def mode(self) -> th.Tensor:
method get_actions (line 168) | def get_actions(self, deterministic: bool = False) -> th.Tensor:
class BetaDistribution (line 174) | class BetaDistribution():
method __init__ (line 175) | def __init__(self, action_dim=2, dist_init=None):
method proba_distribution_net (line 201) | def proba_distribution_net(self, latent_dim: int) -> Tuple[nn.Module, ...
method proba_distribution (line 220) | def proba_distribution(self, alpha, beta):
method log_prob (line 224) | def log_prob(self, actions: th.Tensor) -> th.Tensor:
method entropy_loss (line 228) | def entropy_loss(self) -> th.Tensor:
method exploration_loss (line 232) | def exploration_loss(self, exploration_suggests) -> th.Tensor:
method sample (line 251) | def sample(self) -> th.Tensor:
method mode (line 255) | def mode(self) -> th.Tensor:
method get_actions (line 275) | def get_actions(self, deterministic: bool = False) -> th.Tensor:
FILE: roach/models/ppo.py
class PPO (line 14) | class PPO():
method __init__ (line 15) | def __init__(self, policy, env,
method collect_rollouts (line 66) | def collect_rollouts(self, env: VecEnv, callback: BaseCallback,
method train (line 103) | def train(self):
method learn (line 212) | def learn(self, total_timesteps, callback=None, seed=2021):
method _get_init_kwargs (line 249) | def _get_init_kwargs(self):
method save (line 270) | def save(self, path: str) -> None:
method get_env (line 276) | def get_env(self):
FILE: roach/models/ppo_buffer.py
class PpoBufferSamples (line 23) | class PpoBufferSamples(NamedTuple):
class PpoBuffer (line 35) | class PpoBuffer():
method __init__ (line 36) | def __init__(self, buffer_size: int, observation_space: spaces.Space, ...
method reset (line 56) | def reset(self) -> None:
method compute_returns_and_advantage (line 78) | def compute_returns_and_advantage(self, last_value: th.Tensor, dones: ...
method add (line 98) | def add(self,
method update_values (line 133) | def update_values(self, policy):
method get (line 141) | def get(self, batch_size: Optional[int] = None) -> Generator[PpoBuffer...
method _get_samples (line 166) | def _get_samples(self, batch_inds: np.ndarray) -> PpoBufferSamples:
method flatten (line 188) | def flatten(arr: np.ndarray) -> np.ndarray:
method render (line 195) | def render(self):
method start_caching (line 243) | def start_caching(self, batch_size):
method cache_to_cuda (line 247) | def cache_to_cuda(self, batch_size):
method size (line 255) | def size(self) -> int:
FILE: roach/models/ppo_policy.py
class PpoPolicy (line 11) | class PpoPolicy(nn.Module):
method __init__ (line 13) | def __init__(self,
method reset_noise (line 62) | def reset_noise(self, n_envs: int = 1) -> None:
method _build (line 66) | def _build(self) -> None:
method _get_features (line 102) | def _get_features(self, birdview: th.Tensor, state: th.Tensor) -> th.T...
method _get_action_dist_from_features (line 111) | def _get_action_dist_from_features(self, features: th.Tensor):
method evaluate_actions (line 120) | def evaluate_actions(self, obs_dict: Dict[str, th.Tensor], actions: th...
method evaluate_values (line 136) | def evaluate_values(self, obs_dict: Dict[str, th.Tensor]):
method forward (line 142) | def forward(self, obs_dict: Dict[str, np.ndarray], deterministic: bool...
method forward_value (line 167) | def forward_value(self, obs_dict: Dict[str, np.ndarray]) -> np.ndarray:
method forward_policy (line 175) | def forward_policy(self, obs_dict: Dict[str, np.ndarray]) -> np.ndarray:
method scale_action (line 182) | def scale_action(self, action: th.Tensor, eps=1e-7) -> th.Tensor:
method unscale_action (line 194) | def unscale_action(self, action: np.ndarray, eps=0.0) -> np.ndarray:
method get_init_kwargs (line 208) | def get_init_kwargs(self) -> Dict[str, Any]:
method load (line 222) | def load(cls, path):
method init_weights (line 243) | def init_weights(module: nn.Module, gain: float = 1) -> None:
FILE: roach/models/torch_layers.py
class XtMaCNN (line 10) | class XtMaCNN(nn.Module):
method __init__ (line 15) | def __init__(self, observation_space, features_dim=256, states_neurons...
method _weights_init (line 69) | def _weights_init(m):
method forward (line 74) | def forward(self, birdview, state):
class ImpalaCNN (line 92) | class ImpalaCNN(nn.Module):
method __init__ (line 93) | def __init__(self, observation_space, chans=(16, 32, 32, 64, 64), stat...
method forward (line 121) | def forward(self, birdview, state):
FILE: roach/models/torch_util.py
function NormedLinear (line 7) | def NormedLinear(*args, scale=1.0, dtype=th.float32, **kwargs):
function NormedConv2d (line 18) | def NormedConv2d(*args, scale=1, **kwargs):
function intprod (line 29) | def intprod(xs):
class CnnBasicBlock (line 39) | class CnnBasicBlock(nn.Module):
method __init__ (line 45) | def __init__(self, inchan, scale=1, batch_norm=False):
method residual (line 56) | def residual(self, x):
method forward (line 70) | def forward(self, x):
class CnnDownStack (line 74) | class CnnDownStack(nn.Module):
method __init__ (line 79) | def __init__(self, inchan, nblock, outchan, scale=1, pool=True, **kwar...
method forward (line 90) | def forward(self, x):
method output_shape (line 98) | def output_shape(self, inshape):
FILE: roach/obs_manager/actor_state/control.py
class ObsManager (line 7) | class ObsManager():
method __init__ (line 9) | def __init__(self, obs_configs):
method attach_ego_vehicle (line 11) | def attach_ego_vehicle(self, parent_actor):
method get_observation (line 14) | def get_observation(self):
method clean (line 26) | def clean(self):
FILE: roach/obs_manager/actor_state/route.py
class ObsManager (line 8) | class ObsManager(ObsManagerBase):
method __init__ (line 10) | def __init__(self, obs_configs):
method _define_obs_space (line 15) | def _define_obs_space(self):
method attach_ego_vehicle (line 23) | def attach_ego_vehicle(self, parent_actor):
method get_observation (line 26) | def get_observation(self):
method clean (line 70) | def clean(self):
FILE: roach/obs_manager/actor_state/speed.py
class ObsManager (line 7) | class ObsManager(ObsManagerBase):
method __init__ (line 12) | def __init__(self, obs_configs):
method _define_obs_space (line 16) | def _define_obs_space(self):
method attach_ego_vehicle (line 23) | def attach_ego_vehicle(self, parent_actor):
method get_observation (line 26) | def get_observation(self):
method clean (line 45) | def clean(self):
FILE: roach/obs_manager/actor_state/velocity.py
class ObsManager (line 8) | class ObsManager(ObsManagerBase):
method __init__ (line 10) | def __init__(self, obs_configs):
method _define_obs_space (line 13) | def _define_obs_space(self):
method attach_ego_vehicle (line 23) | def attach_ego_vehicle(self, parent_actor):
method get_observation (line 26) | def get_observation(self):
method clean (line 42) | def clean(self):
FILE: roach/obs_manager/birdview/chauffeurnet.py
function tint (line 27) | def tint(color, factor):
class ObsManager (line 38) | class ObsManager():
method __init__ (line 39) | def __init__(self, obs_configs, criteria_stop=None):
method attach_ego_vehicle (line 60) | def attach_ego_vehicle(self, ego_vehicle):
method _get_stops (line 76) | def _get_stops(criteria_stop):
method get_observation (line 88) | def get_observation(self, route_plan):
method _get_history_masks (line 195) | def _get_history_masks(self, M_warp):
method _get_mask_from_stopline_vtx (line 212) | def _get_mask_from_stopline_vtx(self, stopline_vtx, M_warp):
method _get_mask_from_actor_list (line 221) | def _get_mask_from_actor_list(self, actor_list, M_warp):
method _get_surrounding_actors (line 240) | def _get_surrounding_actors(bbox_list, criterium, scale=None):
method _get_warp_transform (line 255) | def _get_warp_transform(self, ev_loc, ev_rot):
method _world_to_pixel (line 272) | def _world_to_pixel(self, location, projective=False):
method _world_to_pixel_width (line 283) | def _world_to_pixel_width(self, width):
method clean (line 287) | def clean(self):
FILE: roach/obs_manager/birdview/hdmap_generate.py
function tint (line 24) | def tint(color, factor):
FILE: roach/rl_birdview_agent.py
class RlBirdviewAgent (line 9) | class RlBirdviewAgent():
method __init__ (line 10) | def __init__(self, path_to_conf_file='config_agent.yaml', ckpt = None):
method setup (line 17) | def setup(self, path_to_conf_file):
method run_step (line 36) | def run_step(self, input_data, timestamp):
method obs_configs (line 57) | def obs_configs(self):
FILE: roach/utils/config_utils.py
function check_h5_maps (line 12) | def check_h5_maps(env_configs, obs_configs, carla_sh_path):
function load_entry_point (line 51) | def load_entry_point(name):
function load_obs_configs (line 58) | def load_obs_configs(agent_configs_dict):
function init_agents (line 65) | def init_agents(agent_configs_dict, **kwargs):
function parse_routes_file (line 73) | def parse_routes_file(routes_xml_filename):
function get_single_route (line 105) | def get_single_route(routes_xml_filename, route_id):
function to_camel_case (line 131) | def to_camel_case(snake_str, init_capital=False):
function get_free_tcp_port (line 141) | def get_free_tcp_port():
FILE: roach/utils/expert_noiser.py
class ExpertNoiser (line 5) | class ExpertNoiser(object):
method __init__ (line 10) | def __init__(self, noise_type, frequency=15, intensity=10, min_noise_t...
method set_noise (line 26) | def set_noise(self):
method get_noise (line 37) | def get_noise(self):
method get_noise_removing (line 51) | def get_noise_removing(self):
method is_time_for_noise (line 63) | def is_time_for_noise(self, steer):
method set_noise_exist (line 107) | def set_noise_exist(self, noise_exist):
method compute_noise (line 110) | def compute_noise(self, action, speed):
FILE: roach/utils/rl_birdview_wrapper.py
class RlBirdviewWrapper (line 23) | class RlBirdviewWrapper(gym.Wrapper):
method __init__ (line 24) | def __init__(self, env, input_states=[], acc_as_action=False):
method step (line 66) | def step(self, action):
method process_obs (line 90) | def process_obs(obs, input_states, train=True):
method process_act (line 124) | def process_act(action, acc_as_action, train=True):
FILE: roach/utils/traffic_light.py
function _get_traffic_light_waypoints (line 7) | def _get_traffic_light_waypoints(traffic_light, carla_map):
class TrafficLightHandler (line 79) | class TrafficLightHandler:
method reset (line 89) | def reset(world):
method get_light_state (line 114) | def get_light_state(vehicle, offset=0.0, dist_threshold=15.0):
method get_junctoin_paths (line 159) | def get_junctoin_paths(veh_loc, color=0, dist_threshold=50.0):
method get_stopline_vtx (line 181) | def get_stopline_vtx(veh_loc, color, dist_threshold=50.0):
FILE: roach/utils/transforms.py
function loc_global_to_ref (line 5) | def loc_global_to_ref(target_loc_in_global, ref_trans_in_global):
function vec_global_to_ref (line 21) | def vec_global_to_ref(target_vec_in_global, ref_rot_in_global):
function rot_global_to_ref (line 36) | def rot_global_to_ref(target_rot_in_global, ref_rot_in_global):
function rot_ref_to_global (line 44) | def rot_ref_to_global(target_rot_in_ref, ref_rot_in_global):
function carla_rot_to_mat (line 53) | def carla_rot_to_mat(carla_rotation):
function get_loc_rot_vel_in_ev (line 83) | def get_loc_rot_vel_in_ev(actor_list, ev_transform, get_acceleration = F...
function get_loc_rot_in_global (line 117) | def get_loc_rot_in_global(actor_list):
function cast_angle (line 126) | def cast_angle(x):
FILE: roach/utils/wandb_callback.py
class WandbCallback (line 10) | class WandbCallback(BaseCallback):
method __init__ (line 11) | def __init__(self, cfg, vec_env):
method _init_callback (line 33) | def _init_callback(self):
method _on_step (line 38) | def _on_step(self) -> bool:
method _on_training_start (line 41) | def _on_training_start(self) -> None:
method _on_rollout_start (line 44) | def _on_rollout_start(self):
method _on_training_end (line 48) | def _on_training_end(self) -> None:
method _on_rollout_end (line 99) | def _on_rollout_end(self):
method evaluate_policy (line 139) | def evaluate_policy(env, policy, video_path, min_eval_steps=3000):
method get_avg_ep_stat (line 195) | def get_avg_ep_stat(ep_stat_buffer, prefix=''):
FILE: scenario_runner/manual_control.py
function get_actor_display_name (line 72) | def get_actor_display_name(actor, truncate=250):
class WorldSR (line 81) | class WorldSR(World):
method restart (line 85) | def restart(self):
method tick (line 122) | def tick(self, clock):
function game_loop (line 133) | def game_loop(args):
function main (line 176) | def main():
FILE: scenario_runner/metrics_manager.py
class MetricsManager (line 31) | class MetricsManager(object):
method __init__ (line 37) | def __init__(self, args):
method _get_recorder (line 60) | def _get_recorder(self, log):
method _get_criteria (line 81) | def _get_criteria(self, criteria_file):
method _get_metric_class (line 93) | def _get_metric_class(self, metric_file):
method _get_recorder_map (line 116) | def _get_recorder_map(self, recorder_str):
function main (line 127) | def main():
FILE: scenario_runner/no_rendering_mode.py
function get_actor_display_name (line 157) | def get_actor_display_name(actor, truncate=250):
class Util (line 162) | class Util(object):
method blits (line 165) | def blits(destination_surface, source_surfaces, rect=None, blend_mode=0):
method length (line 170) | def length(v):
method get_bounding_box (line 174) | def get_bounding_box(actor):
class ModuleManager (line 191) | class ModuleManager(object):
method __init__ (line 192) | def __init__(self):
method register_module (line 195) | def register_module(self, module):
method clear_modules (line 198) | def clear_modules(self):
method tick (line 201) | def tick(self, clock):
method render (line 206) | def render(self, display):
method get_module (line 211) | def get_module(self, name):
method start_modules (line 216) | def start_modules(self):
class FadingText (line 226) | class FadingText(object):
method __init__ (line 227) | def __init__(self, font, dim, pos):
method set_text (line 234) | def set_text(self, text, color=COLOR_WHITE, seconds=2.0):
method tick (line 241) | def tick(self, clock):
method render (line 246) | def render(self, display):
class HelpText (line 255) | class HelpText(object):
method __init__ (line 256) | def __init__(self, font, width, height):
method toggle (line 270) | def toggle(self):
method render (line 273) | def render(self, display):
class ModuleHUD (line 283) | class ModuleHUD (object):
method __init__ (line 285) | def __init__(self, name, width, height):
method start (line 291) | def start(self):
method _init_hud_params (line 294) | def _init_hud_params(self):
method _init_data_params (line 306) | def _init_data_params(self):
method notification (line 311) | def notification(self, text, seconds=2.0):
method tick (line 314) | def tick(self, clock):
method add_info (line 317) | def add_info(self, module_name, info):
method render_vehicles_ids (line 320) | def render_vehicles_ids(self, vehicle_id_surface, list_actors, world_t...
method render (line 344) | def render(self, display):
class TrafficLightSurfaces (line 396) | class TrafficLightSurfaces(object):
method __init__ (line 399) | def __init__(self):
method rotozoom (line 424) | def rotozoom(self, angle, scale):
class MapImage (line 434) | class MapImage(object):
method __init__ (line 435) | def __init__(self, carla_world, carla_map, pixels_per_meter, show_trig...
method draw_road_map (line 458) | def draw_road_map(self, map_surface, carla_world, carla_map, world_to_...
method world_to_pixel (line 763) | def world_to_pixel(self, location, offset=(0, 0)):
method world_to_pixel_width (line 768) | def world_to_pixel_width(self, width):
method scale_map (line 771) | def scale_map(self, scale):
class ModuleWorld (line 778) | class ModuleWorld(object):
method __init__ (line 779) | def __init__(self, name, args, timeout):
method _get_data_from_carla (line 819) | def _get_data_from_carla(self):
method start (line 836) | def start(self):
method select_hero_actor (line 888) | def select_hero_actor(self):
method _spawn_hero (line 897) | def _spawn_hero(self):
method tick (line 914) | def tick(self, clock):
method update_hud_info (line 921) | def update_hud_info(self, clock):
method on_world_tick (line 966) | def on_world_tick(weak_self, timestamp):
method _split_actors (line 975) | def _split_actors(self):
method _render_traffic_lights (line 1009) | def _render_traffic_lights(self, surface, list_tl, world_to_pixel):
method _render_speed_limits (line 1039) | def _render_speed_limits(self, surface, list_sl, world_to_pixel, world...
method _render_walkers (line 1074) | def _render_walkers(self, surface, list_w, world_to_pixel):
method _render_vehicles (line 1090) | def _render_vehicles(self, surface, list_v, world_to_pixel):
method render_actors (line 1111) | def render_actors(self, surface, vehicles, traffic_lights, speed_limit...
method clip_surfaces (line 1121) | def clip_surfaces(self, clipping_rect):
method _compute_scale (line 1126) | def _compute_scale(self, scale_factor):
method render (line 1147) | def render(self, display):
method destroy (line 1235) | def destroy(self):
class ModuleInput (line 1243) | class ModuleInput(object):
method __init__ (line 1244) | def __init__(self, name):
method start (line 1254) | def start(self):
method render (line 1258) | def render(self, display):
method tick (line 1261) | def tick(self, clock):
method _parse_events (line 1264) | def _parse_events(self):
method _parse_keys (line 1327) | def _parse_keys(self, milliseconds):
method _parse_mouse (line 1342) | def _parse_mouse(self):
method parse_input (line 1349) | def parse_input(self, clock):
method _is_quit_shortcut (line 1361) | def _is_quit_shortcut(key):
function game_loop (line 1376) | def game_loop(args):
function exit_game (line 1418) | def exit_game():
function main (line 1428) | def main():
FILE: scenario_runner/scenario_runner.py
class ScenarioRunner (line 47) | class ScenarioRunner(object):
method __init__ (line 75) | def __init__(self, args):
method destroy (line 114) | def destroy(self):
method _signal_handler (line 127) | def _signal_handler(self, signum, frame):
method _get_scenario_class_or_fail (line 138) | def _get_scenario_class_or_fail(self, scenario):
method _cleanup (line 166) | def _cleanup(self):
method _prepare_ego_vehicles (line 195) | def _prepare_ego_vehicles(self, ego_vehicles):
method _analyze_scenario (line 234) | def _analyze_scenario(self, config):
method _record_criteria (line 258) | def _record_criteria(self, criteria, name):
method _load_and_wait_for_world (line 290) | def _load_and_wait_for_world(self, town, ego_vehicles=None):
method _load_and_run_scenario (line 338) | def _load_and_run_scenario(self, config):
method _run_scenarios (line 415) | def _run_scenarios(self):
method _run_route (line 437) | def _run_route(self):
method _run_openscenario (line 460) | def _run_openscenario(self):
method run (line 477) | def run(self):
function main (line 493) | def main():
FILE: scenario_runner/srunner/autoagents/agent_wrapper.py
class AgentWrapper (line 20) | class AgentWrapper(object):
method __init__ (line 29) | def __init__(self, agent):
method __call__ (line 35) | def __call__(self):
method setup_sensors (line 41) | def setup_sensors(self, vehicle, debug_mode=False):
method cleanup (line 89) | def cleanup(self):
FILE: scenario_runner/srunner/autoagents/autonomous_agent.py
class AutonomousAgent (line 19) | class AutonomousAgent(object):
method __init__ (line 25) | def __init__(self, path_to_conf_file):
method setup (line 36) | def setup(self, path_to_conf_file):
method sensors (line 42) | def sensors(self): # pylint: disable=no-self-use
method run_step (line 64) | def run_step(self, input_data, timestamp):
method destroy (line 77) | def destroy(self):
method __call__ (line 84) | def __call__(self):
method all_sensors_ready (line 100) | def all_sensors_ready(self):
method set_global_plan (line 107) | def set_global_plan(self, global_plan_gps, global_plan_world_coord):
FILE: scenario_runner/srunner/autoagents/dummy_agent.py
class DummyAgent (line 17) | class DummyAgent(AutonomousAgent):
method setup (line 23) | def setup(self, path_to_conf_file):
method sensors (line 28) | def sensors(self):
method run_step (line 61) | def run_step(self, input_data, timestamp):
FILE: scenario_runner/srunner/autoagents/human_agent.py
class HumanInterface (line 34) | class HumanInterface(object):
method __init__ (line 40) | def __init__(self, parent):
method run (line 55) | def run(self):
class HumanAgent (line 91) | class HumanAgent(AutonomousAgent):
method setup (line 100) | def setup(self, path_to_conf_file):
method sensors (line 115) | def sensors(self):
method run_step (line 151) | def run_step(self, input_data, timestamp):
method destroy (line 159) | def destroy(self):
class KeyboardControl (line 167) | class KeyboardControl(object):
method __init__ (line 173) | def __init__(self):
method parse_events (line 180) | def parse_events(self, control, clock):
method _parse_vehicle_keys (line 194) | def _parse_vehicle_keys(self, keys, milliseconds):
FILE: scenario_runner/srunner/autoagents/npc_agent.py
class NpcAgent (line 19) | class NpcAgent(AutonomousAgent):
method setup (line 28) | def setup(self, path_to_conf_file):
method sensors (line 36) | def sensors(self):
method run_step (line 62) | def run_step(self, input_data, timestamp):
FILE: scenario_runner/srunner/autoagents/ros_agent.py
class RosAgent (line 40) | class RosAgent(AutonomousAgent):
method setup (line 65) | def setup(self, path_to_conf_file):
method destroy (line 162) | def destroy(self):
method on_vehicle_control (line 183) | def on_vehicle_control(self, data):
method build_camera_info (line 201) | def build_camera_info(self, attributes): # pylint: disable=no-self-use
method publish_plan (line 224) | def publish_plan(self):
method sensors (line 247) | def sensors(self):
method get_header (line 256) | def get_header(self):
method publish_lidar (line 264) | def publish_lidar(self, sensor_id, data):
method publish_gnss (line 285) | def publish_gnss(self, sensor_id, data):
method publish_camera (line 301) | def publish_camera(self, sensor_id, data):
method publish_can (line 315) | def publish_can(self, sensor_id, data):
method publish_hd_map (line 357) | def publish_hd_map(self, sensor_id, data):
method use_stepping_mode (line 402) | def use_stepping_mode(self): # pylint: disable=no-self-use
method run_step (line 408) | def run_step(self, input_data, timestamp):
FILE: scenario_runner/srunner/autoagents/sensor_interface.py
class CallBack (line 18) | class CallBack(object):
method __init__ (line 24) | def __init__(self, tag, sensor, data_provider):
method __call__ (line 33) | def __call__(self, data):
method _parse_image_cb (line 47) | def _parse_image_cb(self, image, tag):
method _parse_lidar_cb (line 56) | def _parse_lidar_cb(self, lidar_data, tag):
method _parse_gnss_cb (line 65) | def _parse_gnss_cb(self, gnss_data, tag):
class SensorInterface (line 75) | class SensorInterface(object):
method __init__ (line 81) | def __init__(self):
method register_sensor (line 89) | def register_sensor(self, tag, sensor):
method update_sensor (line 100) | def update_sensor(self, tag, data, timestamp):
method all_sensors_ready (line 109) | def all_sensors_ready(self):
method get_data (line 121) | def get_data(self):
FILE: scenario_runner/srunner/metrics/examples/basic_metric.py
class BasicMetric (line 13) | class BasicMetric(object):
method __init__ (line 18) | def __init__(self, town_map, log, criteria=None):
method _create_metric (line 31) | def _create_metric(self, town_map, log, criteria):
FILE: scenario_runner/srunner/metrics/examples/criteria_filter.py
class CriteriaFilter (line 21) | class CriteriaFilter(BasicMetric):
method _create_metric (line 26) | def _create_metric(self, town_map, log, criteria):
FILE: scenario_runner/srunner/metrics/examples/distance_between_vehicles.py
class DistanceBetweenVehicles (line 23) | class DistanceBetweenVehicles(BasicMetric):
method _create_metric (line 28) | def _create_metric(self, town_map, log, criteria):
FILE: scenario_runner/srunner/metrics/examples/distance_to_lane_center.py
class DistanceToLaneCenter (line 22) | class DistanceToLaneCenter(BasicMetric):
method _create_metric (line 27) | def _create_metric(self, town_map, log, criteria):
FILE: scenario_runner/srunner/metrics/tools/metrics_log.py
class MetricsLog (line 20) | class MetricsLog(object): # pylint: disable=too-many-public-methods
method __init__ (line 25) | def __init__(self, recorder):
method get_actor_collisions (line 34) | def get_actor_collisions(self, actor_id):
method get_total_frame_count (line 52) | def get_total_frame_count(self):
method get_elapsed_time (line 59) | def get_elapsed_time(self, frame):
method get_delta_time (line 66) | def get_delta_time(self, frame):
method get_platform_time (line 73) | def get_platform_time(self, frame):
method get_ego_vehicle_id (line 81) | def get_ego_vehicle_id(self):
method get_actor_ids_with_role_name (line 87) | def get_actor_ids_with_role_name(self, role_name):
method get_actor_ids_with_type_id (line 103) | def get_actor_ids_with_type_id(self, type_id):
method get_actor_attributes (line 119) | def get_actor_attributes(self, actor_id):
method get_actor_bounding_box (line 131) | def get_actor_bounding_box(self, actor_id):
method get_traffic_light_trigger_volume (line 146) | def get_traffic_light_trigger_volume(self, traffic_light_id):
method get_actor_alive_frames (line 161) | def get_actor_alive_frames(self, actor_id):
method _get_actor_state (line 184) | def _get_actor_state(self, actor_id, state, frame):
method _get_all_actor_states (line 208) | def _get_all_actor_states(self, actor_id, state, first_frame=None, las...
method _get_states_at_frame (line 234) | def _get_states_at_frame(self, frame, state, actor_list=None):
method get_actor_transform (line 256) | def get_actor_transform(self, actor_id, frame):
method get_all_actor_transforms (line 262) | def get_all_actor_transforms(self, actor_id, first_frame=None, last_fr...
method get_actor_transforms_at_frame (line 268) | def get_actor_transforms_at_frame(self, frame, actor_list=None):
method get_actor_velocity (line 276) | def get_actor_velocity(self, actor_id, frame):
method get_all_actor_velocities (line 282) | def get_all_actor_velocities(self, actor_id, first_frame=None, last_fr...
method get_actor_velocities_at_frame (line 288) | def get_actor_velocities_at_frame(self, frame, actor_list=None):
method get_actor_angular_velocity (line 296) | def get_actor_angular_velocity(self, actor_id, frame):
method get_all_actor_angular_velocities (line 302) | def get_all_actor_angular_velocities(self, actor_id, first_frame=None,...
method get_actor_angular_velocities_at_frame (line 308) | def get_actor_angular_velocities_at_frame(self, frame, actor_list=None):
method get_actor_acceleration (line 316) | def get_actor_acceleration(self, actor_id, frame):
method get_all_actor_accelerations (line 322) | def get_all_actor_accelerations(self, actor_id, first_frame=None, last...
method get_actor_accelerations_at_frame (line 328) | def get_actor_accelerations_at_frame(self, frame, actor_list=None):
method get_vehicle_control (line 336) | def get_vehicle_control(self, vehicle_id, frame):
method get_vehicle_physics_control (line 342) | def get_vehicle_physics_control(self, vehicle_id, frame):
method get_walker_speed (line 356) | def get_walker_speed(self, walker_id, frame):
method get_traffic_light_state (line 363) | def get_traffic_light_state(self, traffic_light_id, frame):
method is_traffic_light_frozen (line 369) | def is_traffic_light_frozen(self, traffic_light_id, frame):
method get_traffic_light_elapsed_time (line 375) | def get_traffic_light_elapsed_time(self, traffic_light_id, frame):
method get_traffic_light_state_time (line 381) | def get_traffic_light_state_time(self, traffic_light_id, state, frame):
method get_vehicle_lights (line 398) | def get_vehicle_lights(self, vehicle_id, frame):
method is_vehicle_light_active (line 404) | def is_vehicle_light_active(self, light, vehicle_id, frame):
method get_scene_light_state (line 416) | def get_scene_light_state(self, light_id, frame):
FILE: scenario_runner/srunner/metrics/tools/metrics_parser.py
function parse_actor (line 17) | def parse_actor(info):
function parse_transform (line 37) | def parse_transform(info):
function parse_control (line 60) | def parse_control(info):
function parse_vehicle_lights (line 80) | def parse_vehicle_lights(info):
function parse_traffic_light (line 109) | def parse_traffic_light(info):
function parse_velocity (line 133) | def parse_velocity(info):
function parse_angular_velocity (line 149) | def parse_angular_velocity(info):
function parse_scene_lights (line 165) | def parse_scene_lights(info):
function parse_bounding_box (line 187) | def parse_bounding_box(info):
function parse_state_times (line 211) | def parse_state_times(info):
function parse_vector_list (line 228) | def parse_vector_list(info):
function parse_gears_control (line 246) | def parse_gears_control(info):
function parse_wheels_control (line 262) | def parse_wheels_control(info):
class MetricsParser (line 282) | class MetricsParser(object):
method __init__ (line 287) | def __init__(self, recorder_info):
method get_row_elements (line 294) | def get_row_elements(self, indent_num, split_string):
method next_row (line 300) | def next_row(self):
method parse_recorder_info (line 307) | def parse_recorder_info(self):
FILE: scenario_runner/srunner/scenarioconfigs/openscenario_configuration.py
class OpenScenarioConfiguration (line 27) | class OpenScenarioConfiguration(ScenarioConfiguration):
method __init__ (line 34) | def __init__(self, filename, client):
method _validate_openscenario_configuration (line 61) | def _validate_openscenario_configuration(self):
method _validate_openscenario_catalog_configuration (line 71) | def _validate_openscenario_catalog_configuration(self, catalog_xml_tree):
method _parse_openscenario_configuration (line 81) | def _parse_openscenario_configuration(self):
method _check_version (line 95) | def _check_version(self):
method _load_catalogs (line 103) | def _load_catalogs(self):
method _set_scenario_name (line 141) | def _set_scenario_name(self):
method _set_carla_town (line 151) | def _set_carla_town(self):
method _set_parameters (line 183) | def _set_parameters(self):
method _set_actor_information (line 199) | def _set_actor_information(self):
method _extract_vehicle_information (line 255) | def _extract_vehicle_information(self, obj, rolename, vehicle, args):
method _extract_pedestrian_information (line 278) | def _extract_pedestrian_information(self, obj, rolename, pedestrian, a...
method _extract_misc_information (line 289) | def _extract_misc_information(self, obj, rolename, misc, args):
method _get_actor_transform (line 304) | def _get_actor_transform(self, actor_name):
method _get_actor_speed (line 342) | def _get_actor_speed(self, actor_name):
method _validate_result (line 370) | def _validate_result(self):
FILE: scenario_runner/srunner/scenarioconfigs/route_scenario_configuration.py
class RouteConfiguration (line 18) | class RouteConfiguration(object):
method __init__ (line 24) | def __init__(self, route=None):
method parse_xml (line 28) | def parse_xml(self, node):
class RouteScenarioConfiguration (line 44) | class RouteScenarioConfiguration(ScenarioConfiguration):
FILE: scenario_runner/srunner/scenarioconfigs/scenario_configuration.py
class ActorConfigurationData (line 15) | class ActorConfigurationData(object):
method __init__ (line 21) | def __init__(self, model, transform, rolename='other', speed=0, autopi...
method parse_from_node (line 34) | def parse_from_node(node, rolename):
class ScenarioConfiguration (line 65) | class ScenarioConfiguration(object):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/actor_control.py
class ActorControl (line 28) | class ActorControl(object):
method __init__ (line 63) | def __init__(self, actor, control_py_module, args):
method reset (line 87) | def reset(self):
method update_target_speed (line 93) | def update_target_speed(self, target_speed, start_time=None):
method update_waypoints (line 105) | def update_waypoints(self, waypoints, start_time=None):
method check_reached_waypoint_goal (line 117) | def check_reached_waypoint_goal(self):
method get_last_longitudinal_command (line 126) | def get_last_longitudinal_command(self):
method get_last_waypoint_command (line 135) | def get_last_waypoint_command(self):
method set_init_speed (line 144) | def set_init_speed(self):
method run_step (line 150) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/basic_control.py
class BasicControl (line 17) | class BasicControl(object):
method __init__ (line 49) | def __init__(self, actor):
method update_target_speed (line 55) | def update_target_speed(self, speed):
method update_waypoints (line 65) | def update_waypoints(self, waypoints, start_time=None):
method set_init_speed (line 75) | def set_init_speed(self):
method check_reached_waypoint_goal (line 81) | def check_reached_waypoint_goal(self):
method reset (line 90) | def reset(self):
method run_step (line 99) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/external_control.py
class ExternalControl (line 19) | class ExternalControl(BasicControl):
method __init__ (line 29) | def __init__(self, actor, args=None):
method reset (line 32) | def reset(self):
method run_step (line 39) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/npc_vehicle_control.py
class NpcVehicleControl (line 22) | class NpcVehicleControl(BasicControl):
method __init__ (line 35) | def __init__(self, actor, args=None):
method _update_plan (line 46) | def _update_plan(self):
method reset (line 57) | def reset(self):
method run_step (line 67) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/pedestrian_control.py
class PedestrianControl (line 19) | class PedestrianControl(BasicControl):
method __init__ (line 28) | def __init__(self, actor, args=None):
method reset (line 34) | def reset(self):
method run_step (line 41) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py
class SimpleVehicleControl (line 29) | class SimpleVehicleControl(BasicControl):
method __init__ (line 77) | def __init__(self, actor, args=None):
method _on_obstacle (line 109) | def _on_obstacle(self, event):
method _on_camera_update (line 121) | def _on_camera_update(self, image):
method reset (line 136) | def reset(self):
method run_step (line 149) | def run_step(self):
method _set_new_velocity (line 211) | def _set_new_velocity(self, next_location):
FILE: scenario_runner/srunner/scenariomanager/actorcontrols/vehicle_longitudinal_control.py
class VehicleLongitudinalControl (line 19) | class VehicleLongitudinalControl(BasicControl):
method __init__ (line 30) | def __init__(self, actor, args=None):
method reset (line 33) | def reset(self):
method run_step (line 40) | def run_step(self):
FILE: scenario_runner/srunner/scenariomanager/carla_data_provider.py
function calculate_velocity (line 23) | def calculate_velocity(actor):
class CarlaDataProvider (line 32) | class CarlaDataProvider(object): # pylint: disable=too-many-public-methods
method register_actor (line 70) | def register_actor(actor):
method register_actors (line 94) | def register_actors(actors):
method on_carla_tick (line 102) | def on_carla_tick():
method get_velocity (line 123) | def get_velocity(actor):
method get_location (line 137) | def get_location(actor):
method get_transform (line 151) | def get_transform(actor):
method set_client (line 165) | def set_client(client):
method get_client (line 172) | def get_client():
method set_ego (line 179) | def set_ego(vehicle):
method get_ego (line 186) | def get_ego():
method set_world (line 193) | def set_world(world):
method set_weather (line 205) | def set_weather(weather):
method get_world (line 212) | def get_world():
method get_map (line 219) | def get_map(world=None):
method is_sync_mode (line 235) | def is_sync_mode():
method find_weather_presets (line 242) | def find_weather_presets():
method prepare_map (line 252) | def prepare_map():
method annotate_trafficlight_in_group (line 270) | def annotate_trafficlight_in_group(traffic_light):
method get_trafficlight_trigger_location (line 306) | def get_trafficlight_trigger_location(traffic_light): # pylint: dis...
method update_light_states (line 330) | def update_light_states(ego_light, annotations, states, freeze=False, ...
method reset_lights (line 362) | def reset_lights(reset_params):
method get_next_traffic_light (line 373) | def get_next_traffic_light(actor, use_cached_location=True):
method set_ego_vehicle_route (line 412) | def set_ego_vehicle_route(route):
method get_ego_vehicle_route (line 421) | def get_ego_vehicle_route():
method generate_spawn_points (line 429) | def generate_spawn_points():
method create_blueprint (line 439) | def create_blueprint(model, rolename='scenario', color=None, actor_cat...
method handle_actor_batch (line 502) | def handle_actor_batch(batch):
method request_new_actor (line 536) | def request_new_actor(model, spawn_point, rolename='scenario', autopil...
method request_new_actors (line 582) | def request_new_actors(actor_list):
method request_new_batch_actors (line 649) | def request_new_batch_actors(model, amount, spawn_points, autopilot=Fa...
method get_actors (line 705) | def get_actors():
method actor_id_exists (line 714) | def actor_id_exists(actor_id):
method get_hero_actor (line 724) | def get_hero_actor():
method get_actor_by_id (line 734) | def get_actor_by_id(actor_id):
method remove_actor_by_id (line 746) | def remove_actor_by_id(actor_id):
method remove_actors_in_surrounding (line 758) | def remove_actors_in_surrounding(location, distance):
method get_traffic_manager_port (line 772) | def get_traffic_manager_port():
method set_traffic_manager_port (line 779) | def set_traffic_manager_port(tm_port):
method set_time_step (line 786) | def set_time_step(time_step):
method get_time_step (line 790) | def get_time_step():
method cleanup (line 797) | def cleanup():
FILE: scenario_runner/srunner/scenariomanager/result_writer.py
class ResultOutputProvider (line 19) | class ResultOutputProvider(object):
method __init__ (line 26) | def __init__(self, data, result, stdout=True, filename=None, junit=None):
method write (line 46) | def write(self):
method create_output_text (line 60) | def create_output_text(self):
method _write_to_junit (line 135) | def _write_to_junit(self):
FILE: scenario_runner/srunner/scenariomanager/scenario_manager.py
class ScenarioManager (line 26) | class ScenarioManager(object):
method __init__ (line 44) | def __init__(self, debug_mode=False, sync_mode=False, timeout=2.0):
method _reset (line 68) | def _reset(self):
method cleanup (line 80) | def cleanup(self):
method load_scenario (line 94) | def load_scenario(self, scenario, agent=None):
method run_scenario (line 114) | def run_scenario(self):
method _tick_scenario (line 149) | def _tick_scenario(self, timestamp):
method get_running_status (line 187) | def get_running_status(self):
method stop_scenario (line 194) | def stop_scenario(self):
method analyze_scenario (line 200) | def analyze_scenario(self, stdout, filename, junit):
FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py
function calculate_distance (line 48) | def calculate_distance(location, other_location, global_planner=None):
function get_actor_control (line 75) | def get_actor_control(actor):
class AtomicBehavior (line 89) | class AtomicBehavior(py_trees.behaviour.Behaviour):
method __init__ (line 100) | def __init__(self, name, actor=None):
method setup (line 109) | def setup(self, unused_timeout=15):
method initialise (line 116) | def initialise(self):
method terminate (line 132) | def terminate(self, new_status):
class RunScript (line 139) | class RunScript(AtomicBehavior):
method __init__ (line 159) | def __init__(self, script, base_path=None, name="RunScript"):
method update (line 168) | def update(self):
class ChangeWeather (line 190) | class ChangeWeather(AtomicBehavior):
method __init__ (line 207) | def __init__(self, weather, name="ChangeWeather"):
method update (line 214) | def update(self):
class ChangeRoadFriction (line 225) | class ChangeRoadFriction(AtomicBehavior):
method __init__ (line 241) | def __init__(self, friction, name="ChangeRoadFriction"):
method update (line 248) | def update(self):
class ChangeActorControl (line 274) | class ChangeActorControl(AtomicBehavior):
method __init__ (line 294) | def __init__(self, actor, control_py_module, args, name="ChangeActorCo...
method update (line 302) | def update(self):
class UpdateAllActorControls (line 329) | class UpdateAllActorControls(AtomicBehavior):
method __init__ (line 341) | def __init__(self, name="UpdateAllActorControls"):
method update (line 347) | def update(self):
class ChangeActorTargetSpeed (line 369) | class ChangeActorTargetSpeed(AtomicBehavior):
method __init__ (line 420) | def __init__(self, actor, target_speed, init_speed=False,
method initialise (line 441) | def initialise(self):
method update (line 481) | def update(self):
class ChangeActorWaypoints (line 531) | class ChangeActorWaypoints(AtomicBehavior):
method __init__ (line 554) | def __init__(self, actor, waypoints, name="ChangeActorWaypoints"):
method initialise (line 563) | def initialise(self):
method update (line 589) | def update(self):
class ChangeActorWaypointsToReachPosition (line 619) | class ChangeActorWaypointsToReachPosition(ChangeActorWaypoints):
method __init__ (line 645) | def __init__(self, actor, position, name="ChangeActorWaypointsToReachP...
method initialise (line 658) | def initialise(self):
class ChangeActorLateralMotion (line 681) | class ChangeActorLateralMotion(AtomicBehavior):
method __init__ (line 719) | def __init__(self, actor, direction='left', distance_lane_change=25,
method initialise (line 736) | def initialise(self):
method update (line 774) | def update(self):
class ActorTransformSetterToOSCPosition (line 815) | class ActorTransformSetterToOSCPosition(AtomicBehavior):
method __init__ (line 835) | def __init__(self, actor, osc_position, physics=True, name="ActorTrans...
method initialise (line 844) | def initialise(self):
method update (line 852) | def update(self):
class AccelerateToVelocity (line 874) | class AccelerateToVelocity(AtomicBehavior):
method __init__ (line 889) | def __init__(self, actor, throttle_value, target_velocity, name="Accel...
method initialise (line 900) | def initialise(self):
method update (line 908) | def update(self):
class AccelerateToCatchUp (line 927) | class AccelerateToCatchUp(AtomicBehavior):
method __init__ (line 947) | def __init__(self, actor, other_actor, throttle_value=1, delta_velocit...
method initialise (line 965) | def initialise(self):
method update (line 971) | def update(self):
class KeepVelocity (line 1006) | class KeepVelocity(AtomicBehavior):
method __init__ (line 1024) | def __init__(self, actor, target_velocity, duration=float("inf"), dist...
method initialise (line 1043) | def initialise(self):
method update (line 1054) | def update(self):
method terminate (line 1084) | def terminate(self, new_status):
class ChangeAutoPilot (line 1099) | class ChangeAutoPilot(AtomicBehavior):
method __init__ (line 1115) | def __init__(self, actor, activate, parameters=None, name="ChangeAutoP...
method update (line 1126) | def update(self):
class StopVehicle (line 1164) | class StopVehicle(AtomicBehavior):
method __init__ (line 1177) | def __init__(self, actor, brake_value, name="Stopping"):
method update (line 1188) | def update(self):
class SyncArrival (line 1210) | class SyncArrival(AtomicBehavior):
method __init__ (line 1229) | def __init__(self, actor, actor_reference, target_location, gain=1, na...
method update (line 1242) | def update(self):
method terminate (line 1276) | def terminate(self, new_status):
class AddNoiseToVehicle (line 1288) | class AddNoiseToVehicle(AtomicBehavior):
method __init__ (line 1302) | def __init__(self, actor, steer_value, throttle_value, name="Jittering"):
method update (line 1312) | def update(self):
class ChangeNoiseParameters (line 1327) | class ChangeNoiseParameters(AtomicBehavior):
method __init__ (line 1338) | def __init__(self, new_steer_noise, new_throttle_noise,
method update (line 1354) | def update(self):
class BasicAgentBehavior (line 1367) | class BasicAgentBehavior(AtomicBehavior):
method __init__ (line 1384) | def __init__(self, actor, target_location, name="BasicAgentBehavior"):
method update (line 1395) | def update(self):
method terminate (line 1409) | def terminate(self, new_status):
class Idle (line 1416) | class Idle(AtomicBehavior):
method __init__ (line 1428) | def __init__(self, duration=float("inf"), name="Idle"):
method initialise (line 1437) | def initialise(self):
method update (line 1444) | def update(self):
class WaypointFollower (line 1456) | class WaypointFollower(AtomicBehavior):
method __init__ (line 1498) | def __init__(self, actor, target_speed=None, plan=None, blackboard_que...
method initialise (line 1517) | def initialise(self):
method _apply_local_planner (line 1544) | def _apply_local_planner(self, actor):
method update (line 1582) | def update(self):
method terminate (line 1657) | def terminate(self, new_status):
class LaneChange (line 1676) | class LaneChange(WaypointFollower):
method __init__ (line 1700) | def __init__(self, actor, speed=10, direction='left',
method initialise (line 1714) | def initialise(self):
method update (line 1725) | def update(self):
class SetInitSpeed (line 1745) | class SetInitSpeed(AtomicBehavior):
method __init__ (line 1752) | def __init__(self, actor, init_speed=10, name='SetInitSpeed'):
method initialise (line 1760) | def initialise(self):
method update (line 1772) | def update(self):
class HandBrakeVehicle (line 1780) | class HandBrakeVehicle(AtomicBehavior):
method __init__ (line 1793) | def __init__(self, vehicle, hand_brake_value, name="Braking"):
method update (line 1803) | def update(self):
class ActorDestroy (line 1820) | class ActorDestroy(AtomicBehavior):
method __init__ (line 1832) | def __init__(self, actor, name="ActorDestroy"):
method update (line 1839) | def update(self):
class ActorTransformSetter (line 1849) | class ActorTransformSetter(AtomicBehavior):
method __init__ (line 1869) | def __init__(self, actor, transform, physics=True, name="ActorTransfor...
method initialise (line 1878) | def initialise(self):
method update (line 1885) | def update(self):
class TrafficLightStateSetter (line 1902) | class TrafficLightStateSetter(AtomicBehavior):
method __init__ (line 1914) | def __init__(self, actor, state, name="TrafficLightStateSetter"):
method update (line 1924) | def update(self):
class ActorSource (line 1942) | class ActorSource(AtomicBehavior):
method __init__ (line 1959) | def __init__(self, actor_type_list, transform, threshold, blackboard_q...
method update (line 1973) | def update(self):
class ActorSink (line 2000) | class ActorSink(AtomicBehavior):
method __init__ (line 2014) | def __init__(self, sink_location, threshold, name="ActorSink"):
method update (line 2022) | def update(self):
class StartRecorder (line 2028) | class StartRecorder(AtomicBehavior):
method __init__ (line 2043) | def __init__(self, recorder_name, name="StartRecorder"):
method update (line 2051) | def update(self):
class StopRecorder (line 2056) | class StopRecorder(AtomicBehavior):
method __init__ (line 2065) | def __init__(self, name="StopRecorder"):
method update (line 2072) | def update(self):
class TrafficLightManipulator (line 2077) | class TrafficLightManipulator(AtomicBehavior):
method __init__ (line 2129) | def __init__(self, ego_vehicle, subtype, debug=False, name="TrafficLig...
method update (line 2149) | def update(self):
method passed_enough_time (line 2265) | def passed_enough_time(self, time_limit):
method set_intersection_state (line 2288) | def set_intersection_state(self, choice):
method get_waiting_time (line 2300) | def get_waiting_time(self, annotation, direction):
method get_traffic_light_configuration (line 2316) | def get_traffic_light_configuration(self, subtype, annotations):
method variable_cleanup (line 2353) | def variable_cleanup(self):
class ScenarioTriggerer (line 2368) | class ScenarioTriggerer(AtomicBehavior):
method __init__ (line 2379) | def __init__(self, actor, route, blackboard_list, distance,
method update (line 2400) | def update(self):
FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_criteria.py
class Criterion (line 31) | class Criterion(py_trees.behaviour.Behaviour):
method __init__ (line 47) | def __init__(self,
method initialise (line 67) | def initialise(self):
method terminate (line 73) | def terminate(self, new_status):
class MaxVelocityTest (line 83) | class MaxVelocityTest(Criterion):
method __init__ (line 94) | def __init__(self, actor, max_velocity_allowed, optional=False, name="...
method update (line 100) | def update(self):
class DrivenDistanceTest (line 126) | class DrivenDistanceTest(Criterion):
method __init__ (line 140) | def __init__(self,
method initialise (line 152) | def initialise(self):
method update (line 156) | def update(self):
method terminate (line 192) | def terminate(self, new_status):
class AverageVelocityTest (line 202) | class AverageVelocityTest(Criterion):
method __init__ (line 216) | def __init__(self,
method initialise (line 232) | def initialise(self):
method update (line 236) | def update(self):
method terminate (line 276) | def terminate(self, new_status):
class CollisionTest (line 285) | class CollisionTest(Criterion):
method __init__ (line 303) | def __init__(self, actor, other_actor=None, other_actor_type=None,
method update (line 322) | def update(self):
method terminate (line 354) | def terminate(self, new_status):
method _count_collisions (line 365) | def _count_collisions(weak_self, event): # pylint: disable=too-man...
class ActorSpeedAboveThresholdTest (line 440) | class ActorSpeedAboveThresholdTest(Criterion):
method __init__ (line 452) | def __init__(self, actor, speed_threshold, below_threshold_max_time,
method update (line 464) | def update(self):
method _set_event_message (line 493) | def _set_event_message(event, location):
method _set_event_dict (line 504) | def _set_event_dict(event, location):
class KeepLaneTest (line 515) | class KeepLaneTest(Criterion):
method __init__ (line 525) | def __init__(self, actor, optional=False, name="CheckKeepLane"):
method update (line 537) | def update(self):
method terminate (line 555) | def terminate(self, new_status):
method _count_lane_invasion (line 565) | def _count_lane_invasion(weak_self, event):
class ReachedRegionTest (line 575) | class ReachedRegionTest(Criterion):
method __init__ (line 586) | def __init__(self, actor, min_x, max_x, min_y, max_y, name="ReachedReg...
method update (line 599) | def update(self):
class OffRoadTest (line 626) | class OffRoadTest(Criterion):
method __init__ (line 642) | def __init__(self, actor, duration=0, optional=False, terminate_on_fai...
method update (line 656) | def update(self):
class EndofRoadTest (line 707) | class EndofRoadTest(Criterion):
method __init__ (line 721) | def __init__(self, actor, duration=0, optional=False, terminate_on_fai...
method update (line 736) | def update(self):
class OnSidewalkTest (line 776) | class OnSidewalkTest(Criterion):
method __init__ (line 791) | def __init__(self, actor, duration=0, optional=False, terminate_on_fai...
method update (line 812) | def update(self):
method terminate (line 977) | def terminate(self, new_status):
method _set_event_message (line 1013) | def _set_event_message(self, event, location, distance):
method _set_event_dict (line 1031) | def _set_event_dict(self, event, location, distance):
class OutsideRouteLanesTest (line 1042) | class OutsideRouteLanesTest(Criterion):
method __init__ (line 1059) | def __init__(self, actor, route, optional=False, name="OutsideRouteLan...
method update (line 1082) | def update(self):
method _is_outside_driving_lanes (line 1137) | def _is_outside_driving_lanes(self, location):
method _is_at_wrong_lane (line 1160) | def _is_at_wrong_lane(self, location):
method terminate (line 1209) | def terminate(self, new_status):
class WrongLaneTest (line 1238) | class WrongLaneTest(Criterion):
method __init__ (line 1250) | def __init__(self, actor, optional=False, name="WrongLaneTest"):
method update (line 1268) | def update(self):
method terminate (line 1362) | def terminate(self, new_status):
method _set_event_message (line 1384) | def _set_event_message(self, event, location, distance, road_id, lane_...
method _set_event_dict (line 1400) | def _set_event_dict(self, event, location, distance, road_id, lane_id):
class InRadiusRegionTest (line 1413) | class InRadiusRegionTest(Criterion):
method __init__ (line 1423) | def __init__(self, actor, x, y, radius, name="InRadiusRegionTest"):
method update (line 1433) | def update(self):
class InRouteTest (line 1461) | class InRouteTest(Criterion):
method __init__ (line 1477) | def __init__(self, actor, route, offroad_min=-1, offroad_max=30, name=...
method update (line 1514) | def update(self):
class RouteCompletionTest (line 1593) | class RouteCompletionTest(Criterion):
method __init__ (line 1606) | def __init__(self, actor, route, name="RouteCompletionTest", terminate...
method update (line 1637) | def update(self):
method terminate (line 1685) | def terminate(self, new_status):
class RunningRedLightTest (line 1696) | class RunningRedLightTest(Criterion):
method __init__ (line 1707) | def __init__(self, actor, name="RunningRedLightTest", terminate_on_fai...
method is_vehicle_crossing_line (line 1728) | def is_vehicle_crossing_line(self, seg1, seg2):
method update (line 1738) | def update(self):
method rotate_point (line 1836) | def rotate_point(self, point, angle):
method get_traffic_light_waypoints (line 1844) | def get_traffic_light_waypoints(self, traffic_light):
class RunningStopTest (line 1884) | class RunningStopTest(Criterion):
method __init__ (line 1897) | def __init__(self, actor, name="RunningStopTest", terminate_on_failure...
method point_inside_boundingbox (line 1917) | def point_inside_boundingbox(point, bb_center, bb_extent):
method is_actor_affected_by_stop (line 1942) | def is_actor_affected_by_stop(self, actor, stop, multi_step=20):
method _scan_for_stop_sign (line 1975) | def _scan_for_stop_sign(self):
method update (line 1995) | def update(self):
FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py
class AtomicCondition (line 42) | class AtomicCondition(py_trees.behaviour.Behaviour):
method __init__ (line 53) | def __init__(self, name):
method setup (line 61) | def setup(self, unused_timeout=15):
method initialise (line 68) | def initialise(self):
method terminate (line 74) | def terminate(self, new_status):
class InTriggerDistanceToOSCPosition (line 81) | class InTriggerDistanceToOSCPosition(AtomicCondition):
method __init__ (line 96) | def __init__(self, actor, osc_position, distance, along_route=False,
method initialise (line 118) | def initialise(self):
method update (line 122) | def update(self):
class InTimeToArrivalToOSCPosition (line 149) | class InTimeToArrivalToOSCPosition(AtomicCondition):
method __init__ (line 164) | def __init__(self, actor, osc_position, time, along_route=False,
method initialise (line 186) | def initialise(self):
method update (line 190) | def update(self):
class StandStill (line 230) | class StandStill(AtomicCondition):
method __init__ (line 243) | def __init__(self, actor, name, duration=float("inf")):
method initialise (line 254) | def initialise(self):
method update (line 261) | def update(self):
class RelativeVelocityToOtherActor (line 280) | class RelativeVelocityToOtherActor(AtomicCondition):
method __init__ (line 295) | def __init__(self, actor, other_actor, speed, comparison_operator=oper...
method update (line 307) | def update(self):
class TriggerVelocity (line 330) | class TriggerVelocity(AtomicCondition):
method __init__ (line 344) | def __init__(self, actor, target_velocity, comparison_operator=operato...
method update (line 354) | def update(self):
class TriggerAcceleration (line 374) | class TriggerAcceleration(AtomicCondition):
method __init__ (line 388) | def __init__(self, actor, target_acceleration, comparison_operator=ope...
method update (line 398) | def update(self):
class TimeOfDayComparison (line 421) | class TimeOfDayComparison(AtomicCondition):
method __init__ (line 435) | def __init__(self, dattime, comparison_operator=operator.gt, name="Tim...
method update (line 443) | def update(self):
class OSCStartEndCondition (line 467) | class OSCStartEndCondition(AtomicCondition):
method __init__ (line 480) | def __init__(self, element_type, element_name, rule, name="OSCStartEnd...
method initialise (line 492) | def initialise(self):
method update (line 499) | def update(self):
class InTriggerRegion (line 516) | class InTriggerRegion(AtomicCondition):
method __init__ (line 529) | def __init__(self, actor, min_x, max_x, min_y, max_y, name="TriggerReg...
method update (line 542) | def update(self):
class InTriggerDistanceToVehicle (line 563) | class InTriggerDistanceToVehicle(AtomicCondition):
method __init__ (line 579) | def __init__(self, reference_actor, actor, distance, comparison_operat...
method update (line 591) | def update(self):
class InTriggerDistanceToLocation (line 611) | class InTriggerDistanceToLocation(AtomicCondition):
method __init__ (line 626) | def __init__(self,
method update (line 642) | def update(self):
class InTriggerDistanceToNextIntersection (line 663) | class InTriggerDistanceToNextIntersection(AtomicCondition):
method __init__ (line 677) | def __init__(self, actor, distance, name="InTriggerDistanceToNextInter...
method update (line 693) | def update(self):
class InTriggerDistanceToLocationAlongRoute (line 710) | class InTriggerDistanceToLocationAlongRoute(AtomicCondition):
method __init__ (line 727) | def __init__(self, actor, route, location, distance, name="InTriggerDi...
method update (line 740) | def update(self):
class InTimeToArrivalToLocation (line 761) | class InTimeToArrivalToLocation(AtomicCondition):
method __init__ (line 778) | def __init__(self, actor, time, location, comparison_operator=operator...
method update (line 789) | def update(self):
class InTimeToArrivalToVehicle (line 816) | class InTimeToArrivalToVehicle(AtomicCondition):
method __init__ (line 833) | def __init__(self, actor, other_actor, time, along_route=False,
method update (line 856) | def update(self):
class InTimeToArrivalToVehicleSideLane (line 892) | class InTimeToArrivalToVehicleSideLane(InTimeToArrivalToLocation):
method __init__ (line 910) | def __init__(self, actor, other_actor, time, side_lane,
method update (line 937) | def update(self):
class WaitUntilInFront (line 965) | class WaitUntilInFront(AtomicCondition):
method __init__ (line 978) | def __init__(self, actor, other_actor, factor=1, check_distance=True, ...
method update (line 998) | def update(self):
class DriveDistance (line 1042) | class DriveDistance(AtomicCondition):
method __init__ (line 1054) | def __init__(self, actor, distance, name="DriveDistance"):
method initialise (line 1065) | def initialise(self):
method update (line 1069) | def update(self):
class AtRightmostLane (line 1086) | class AtRightmostLane(AtomicCondition):
method __init__ (line 1097) | def __init__(self, actor, name="AtRightmostLane"):
method update (line 1106) | def update(self):
class WaitForTrafficLightState (line 1128) | class WaitForTrafficLightState(AtomicCondition):
method __init__ (line 1141) | def __init__(self, actor, state, name="WaitForTrafficLightState"):
method update (line 1150) | def update(self):
class WaitEndIntersection (line 1167) | class WaitEndIntersection(AtomicCondition):
method __init__ (line 1174) | def __init__(self, actor, debug=False, name="WaitEndIntersection"):
method update (line 1181) | def update(self):
class WaitForBlackboardVariable (line 1201) | class WaitForBlackboardVariable(AtomicCondition):
method __init__ (line 1210) | def __init__(self, variable_name, variable_value, var_init_value=None,
method update (line 1222) | def update(self):
FILE: scenario_runner/srunner/scenariomanager/timer.py
class GameTime (line 17) | class GameTime(object):
method on_carla_tick (line 33) | def on_carla_tick(timestamp):
method restart (line 47) | def restart():
method get_time (line 55) | def get_time():
method get_carla_time (line 62) | def get_carla_time():
method get_wallclocktime (line 69) | def get_wallclocktime():
method get_frame (line 76) | def get_frame():
class SimulationTimeCondition (line 83) | class SimulationTimeCondition(py_trees.behaviour.Behaviour):
method __init__ (line 94) | def __init__(self, timeout, success_rule="greaterThan", name="Simulati...
method initialise (line 107) | def initialise(self):
method update (line 114) | def update(self):
class TimeOut (line 133) | class TimeOut(SimulationTimeCondition):
method __init__ (line 141) | def __init__(self, timeout, name="TimeOut"):
method update (line 148) | def update(self):
FILE: scenario_runner/srunner/scenariomanager/traffic_events.py
class TrafficEventType (line 13) | class TrafficEventType(Enum):
class TrafficEvent (line 35) | class TrafficEvent(object):
method __init__ (line 41) | def __init__(self, event_type, message=None, dictionary=None):
method get_type (line 53) | def get_type(self):
method get_message (line 59) | def get_message(self):
method set_message (line 68) | def set_message(self, message):
method get_dict (line 74) | def get_dict(self):
method set_dict (line 80) | def set_dict(self, dictionary):
FILE: scenario_runner/srunner/scenariomanager/watchdog.py
class Watchdog (line 21) | class Watchdog(object):
method __init__ (line 35) | def __init__(self, timeout=1.0):
method start (line 43) | def start(self):
method update (line 51) | def update(self):
method _event (line 58) | def _event(self):
method stop (line 68) | def stop(self):
method get_status (line 74) | def get_status(self):
FILE: scenario_runner/srunner/scenariomanager/weather_sim.py
class Weather (line 26) | class Weather(object):
method __init__ (line 51) | def __init__(self, carla_weather, dtime=None, animation=False):
method update (line 70) | def update(self, delta_time=0):
class WeatherBehavior (line 90) | class WeatherBehavior(py_trees.behaviour.Behaviour):
method __init__ (line 110) | def __init__(self, name="WeatherBehavior"):
method initialise (line 118) | def initialise(self):
method update (line 124) | def update(self):
FILE: scenario_runner/srunner/scenarios/background_activity.py
class BackgroundActivity (line 16) | class BackgroundActivity(BasicScenario):
method __init__ (line 38) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 55) | def _initialize_actors(self, config):
method _create_behavior (line 81) | def _create_behavior(self):
method _create_test_criteria (line 87) | def _create_test_criteria(self):
method __del__ (line 94) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/basic_scenario.py
class BasicScenario (line 26) | class BasicScenario(object):
method __init__ (line 32) | def __init__(self, name, ego_vehicles, config, world,
method _initialize_environment (line 85) | def _initialize_environment(self, world):
method _initialize_actors (line 108) | def _initialize_actors(self, config):
method _setup_scenario_trigger (line 121) | def _setup_scenario_trigger(self, config):
method _setup_scenario_end (line 154) | def _setup_scenario_end(self, config):
method _create_behavior (line 171) | def _create_behavior(self):
method _create_test_criteria (line 179) | def _create_test_criteria(self):
method change_control (line 188) | def change_control(self, control): # pylint: disable=no-self-use
method remove_all_actors (line 198) | def remove_all_actors(self):
class Scenario (line 210) | class Scenario(object):
method __init__ (line 225) | def __init__(self, behavior, criteria, name, timeout=60, terminate_on_...
method _extract_nodes_from_tree (line 261) | def _extract_nodes_from_tree(self, tree): # pylint: disable=no-self-use
method get_criteria (line 281) | def get_criteria(self):
method terminate (line 288) | def terminate(self):
FILE: scenario_runner/srunner/scenarios/change_lane.py
class ChangeLane (line 36) | class ChangeLane(BasicScenario):
method __init__ (line 50) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 85) | def _initialize_actors(self, config):
method _create_behavior (line 111) | def _create_behavior(self):
method _create_test_criteria (line 164) | def _create_test_criteria(self):
method __del__ (line 177) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/control_loss.py
class ControlLoss (line 29) | class ControlLoss(BasicScenario):
method __init__ (line 37) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 72) | def _initialize_actors(self, config):
method _create_behavior (line 121) | def _create_behavior(self):
method _create_test_criteria (line 171) | def _create_test_criteria(self):
method change_control (line 183) | def change_control(self, control):
method __del__ (line 194) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/cut_in.py
class CutIn (line 32) | class CutIn(BasicScenario):
method __init__ (line 41) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 68) | def _initialize_actors(self, config):
method _create_behavior (line 91) | def _create_behavior(self):
method _create_test_criteria (line 142) | def _create_test_criteria(self):
method __del__ (line 154) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/follow_leading_vehicle.py
class FollowLeadingVehicle (line 41) | class FollowLeadingVehicle(BasicScenario):
method __init__ (line 52) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 87) | def _initialize_actors(self, config):
method _create_behavior (line 107) | def _create_behavior(self):
method _create_test_criteria (line 155) | def _create_test_criteria(self):
method __del__ (line 168) | def __del__(self):
class FollowLeadingVehicleWithObstacle (line 175) | class FollowLeadingVehicleWithObstacle(BasicScenario):
method __init__ (line 186) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 209) | def _initialize_actors(self, config):
method _create_behavior (line 250) | def _create_behavior(self):
method _create_test_criteria (line 308) | def _create_test_criteria(self):
method __del__ (line 321) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/freeride.py
class FreeRide (line 19) | class FreeRide(BasicScenario):
method __init__ (line 25) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _setup_scenario_trigger (line 39) | def _setup_scenario_trigger(self, config):
method _create_behavior (line 44) | def _create_behavior(self):
method _create_test_criteria (line 51) | def _create_test_criteria(self):
method __del__ (line 64) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/junction_crossing_route.py
class SignalJunctionCrossingRoute (line 23) | class SignalJunctionCrossingRoute(BasicScenario):
method __init__ (line 40) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 57) | def _initialize_actors(self, config):
method _create_behavior (line 62) | def _create_behavior(self):
method _create_test_criteria (line 88) | def _create_test_criteria(self):
method __del__ (line 110) | def __del__(self):
class NoSignalJunctionCrossingRoute (line 118) | class NoSignalJunctionCrossingRoute(BasicScenario):
method __init__ (line 131) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 147) | def _initialize_actors(self, config):
method _create_behavior (line 152) | def _create_behavior(self):
method _create_test_criteria (line 177) | def _create_test_criteria(self):
method __del__ (line 199) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/maneuver_opposite_direction.py
class ManeuverOppositeDirection (line 32) | class ManeuverOppositeDirection(BasicScenario):
method __init__ (line 40) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 74) | def _initialize_actors(self, config):
method _create_behavior (line 118) | def _create_behavior(self):
method _create_test_criteria (line 156) | def _create_test_criteria(self):
method __del__ (line 168) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/master_scenario.py
class MasterScenario (line 25) | class MasterScenario(BasicScenario):
method __init__ (line 35) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _create_behavior (line 54) | def _create_behavior(self):
method _create_test_criteria (line 66) | def _create_test_criteria(self):
method __del__ (line 110) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/no_signal_junction_crossing.py
class NoSignalJunctionCrossing (line 28) | class NoSignalJunctionCrossing(BasicScenario):
method __init__ (line 46) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 63) | def _initialize_actors(self, config):
method _create_behavior (line 77) | def _create_behavior(self):
method _create_test_criteria (line 148) | def _create_test_criteria(self):
method __del__ (line 160) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/object_crash_intersection.py
function get_opponent_transform (line 33) | def get_opponent_transform(added_dist, waypoint, trigger_location):
function get_right_driving_lane (line 60) | def get_right_driving_lane(waypoint):
function is_lane_a_parking (line 85) | def is_lane_a_parking(waypoint):
class VehicleTurningRight (line 107) | class VehicleTurningRight(BasicScenario):
method __init__ (line 118) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 146) | def _initialize_actors(self, config):
method _create_behavior (line 192) | def _create_behavior(self):
method _create_test_criteria (line 256) | def _create_test_criteria(self):
method __del__ (line 267) | def __del__(self):
class VehicleTurningLeft (line 274) | class VehicleTurningLeft(BasicScenario):
method __init__ (line 285) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 313) | def _initialize_actors(self, config):
method _create_behavior (line 359) | def _create_behavior(self):
method _create_test_criteria (line 423) | def _create_test_criteria(self):
method __del__ (line 434) | def __del__(self):
class VehicleTurningRoute (line 441) | class VehicleTurningRoute(BasicScenario):
method __init__ (line 453) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 481) | def _initialize_actors(self, config):
method _create_behavior (line 527) | def _create_behavior(self):
method _create_test_criteria (line 591) | def _create_test_criteria(self):
method __del__ (line 602) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/object_crash_vehicle.py
class StationaryObjectCrossing (line 33) | class StationaryObjectCrossing(BasicScenario):
method __init__ (line 44) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 66) | def _initialize_actors(self, config):
method _create_behavior (line 87) | def _create_behavior(self):
method _create_test_criteria (line 114) | def _create_test_criteria(self):
method __del__ (line 126) | def __del__(self):
class DynamicObjectCrossing (line 133) | class DynamicObjectCrossing(BasicScenario):
method __init__ (line 144) | def __init__(self, world, ego_vehicles, config, randomize=False,
method _calculate_base_transform (line 179) | def _calculate_base_transform(self, _start_distance, waypoint):
method _spawn_adversary (line 201) | def _spawn_adversary(self, transform, orientation_yaw):
method _spawn_blocker (line 218) | def _spawn_blocker(self, transform, orientation_yaw):
method _initialize_actors (line 243) | def _initialize_actors(self, config):
method _create_behavior (line 303) | def _create_behavior(self):
method _create_test_criteria (line 388) | def _create_test_criteria(self):
method __del__ (line 400) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/open_scenario.py
function repeatable_behavior (line 25) | def repeatable_behavior(behaviour, name=None):
class ClearBlackboardVariablesStartingWith (line 46) | class ClearBlackboardVariablesStartingWith(py_trees.behaviours.Success):
method __init__ (line 56) | def __init__(self,
method initialise (line 63) | def initialise(self):
class StoryElementStatusToBlackboard (line 73) | class StoryElementStatusToBlackboard(Decorator):
method __init__ (line 84) | def __init__(self, child, story_element_type, element_name):
method initialise (line 90) | def initialise(self):
method update (line 101) | def update(self):
method terminate (line 108) | def terminate(self, new_status):
function get_xml_path (line 147) | def get_xml_path(tree, node):
class OpenScenario (line 170) | class OpenScenario(BasicScenario):
method __init__ (line 176) | def __init__(self, world, ego_vehicles, config, config_file, debug_mod...
method _initialize_environment (line 190) | def _initialize_environment(self, world):
method _create_environment_behavior (line 196) | def _create_environment_behavior(self):
method _create_init_behavior (line 211) | def _create_init_behavior(self):
method _create_behavior (line 245) | def _create_behavior(self):
method _create_condition_container (line 396) | def _create_condition_container(self, node, name='Conditions Group', s...
method _create_test_criteria (line 430) | def _create_test_criteria(self):
method __del__ (line 451) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/opposite_vehicle_taking_priority.py
class OppositeVehicleRunningRedLight (line 36) | class OppositeVehicleRunningRedLight(BasicScenario):
method __init__ (line 61) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 99) | def _initialize_actors(self, config):
method _create_behavior (line 112) | def _create_behavior(self):
method _create_test_criteria (line 195) | def _create_test_criteria(self):
method __del__ (line 222) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/other_leading_vehicle.py
class OtherLeadingVehicle (line 33) | class OtherLeadingVehicle(BasicScenario):
method __init__ (line 43) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 69) | def _initialize_actors(self, config):
method _create_behavior (line 91) | def _create_behavior(self):
method _create_test_criteria (line 138) | def _create_test_criteria(self):
method __del__ (line 150) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/route_scenario.py
function convert_json_to_transform (line 67) | def convert_json_to_transform(actor_dict):
function convert_json_to_actor (line 76) | def convert_json_to_actor(actor_dict):
function convert_transform_to_location (line 89) | def convert_transform_to_location(transform_vec):
function compare_scenarios (line 100) | def compare_scenarios(scenario_choice, existent_scenario):
class RouteScenario (line 138) | class RouteScenario(BasicScenario):
method __init__ (line 145) | def __init__(self, world, config, debug_mode=False, criteria_enable=Tr...
method _update_route (line 174) | def _update_route(self, world, config, debug_mode):
method _update_ego_vehicle (line 206) | def _update_ego_vehicle(self):
method _estimate_route_timeout (line 220) | def _estimate_route_timeout(self):
method _draw_waypoints (line 235) | def _draw_waypoints(self, world, waypoints, vertical_shift, persistenc...
method _scenario_sampling (line 264) | def _scenario_sampling(self, potential_scenarios_definitions, random_s...
method _build_scenario_instances (line 303) | def _build_scenario_instances(self, world, ego_vehicle, scenario_defin...
method _get_actors_instances (line 362) | def _get_actors_instances(self, list_of_antagonist_actors):
method _initialize_actors (line 392) | def _initialize_actors(self, config):
method _create_behavior (line 435) | def _create_behavior(self):
method _create_test_criteria (line 479) | def _create_test_criteria(self):
method __del__ (line 517) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/signalized_junction_left_turn.py
class SignalizedJunctionLeftTurn (line 30) | class SignalizedJunctionLeftTurn(BasicScenario):
method __init__ (line 42) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 74) | def _initialize_actors(self, config):
method _create_behavior (line 89) | def _create_behavior(self):
method _create_test_criteria (line 136) | def _create_test_criteria(self):
method __del__ (line 148) | def __del__(self):
FILE: scenario_runner/srunner/scenarios/signalized_junction_right_turn.py
class SignalizedJunctionRightTurn (line 35) | class SignalizedJunctionRightTurn(BasicScenario):
method __init__ (line 45) | def __init__(self, world, ego_vehicles, config, randomize=False, debug...
method _initialize_actors (line 78) | def _initialize_actors(self, config):
method _create_behavior (line 92) | def _create_behavior(self):
method _create_test_criteria (line 148) | def _create_test_criteria(self):
method __del__ (line 160) | def __del__(self):
FILE: scenario_runner/srunner/tools/openscenario_parser.py
class OpenScenarioParser (line 69) | class OpenScenarioParser(object):
method get_traffic_light_from_osc_name (line 98) | def get_traffic_light_from_osc_name(name):
method set_osc_filepath (line 130) | def set_osc_filepath(filepath):
method set_use_carla_coordinate_system (line 138) | def set_use_carla_coordinate_system():
method set_parameters (line 147) | def set_parameters(xml_tree, additional_parameter_dict=None):
method set_global_parameters (line 189) | def set_global_parameters(parameter_dict):
method get_catalog_entry (line 199) | def get_catalog_entry(catalogs, catalog_reference):
method assign_catalog_parameters (line 219) | def assign_catalog_parameters(entry_instance, catalog_reference):
method get_friction_from_env_action (line 260) | def get_friction_from_env_action(xml_tree, catalogs):
method get_weather_from_env_action (line 289) | def get_weather_from_env_action(xml_tree, catalogs):
method get_controller (line 340) | def get_controller(xml_tree, catalogs):
method get_route (line 379) | def get_route(xml_tree, catalogs):
method convert_position_to_transform (line 411) | def convert_position_to_transform(position, actor_list=None):
method convert_condition_to_atomic (line 590) | def convert_condition_to_atomic(condition, actor_list):
method convert_maneuver_to_atomic (line 895) | def convert_maneuver_to_atomic(action, actor, catalogs):
FILE: scenario_runner/srunner/tools/py_trees_port.py
class Decorator (line 18) | class Decorator(py_trees.behaviour.Behaviour):
method __init__ (line 28) | def __init__(self, child, name):
method tick (line 48) | def tick(self):
method stop (line 74) | def stop(self, new_status=py_trees.common.Status.INVALID):
method tip (line 91) | def tip(self):
function oneshot_behavior (line 103) | def oneshot_behavior(variable_name, behaviour, name=None):
FILE: scenario_runner/srunner/tools/route_manipulation.py
function _location_to_gps (line 22) | def _location_to_gps(lat_ref, lon_ref, location):
function location_route_to_gps (line 45) | def location_route_to_gps(route, lat_ref, lon_ref):
function _get_latlon_ref (line 62) | def _get_latlon_ref(world):
function downsample_route (line 87) | def downsample_route(route, sample_factor):
function interpolate_trajectory (line 133) | def interpolate_trajectory(world, waypoints_trajectory, hop_resolution=1...
FILE: scenario_runner/srunner/tools/route_parser.py
class RouteParser (line 23) | class RouteParser(object):
method parse_annotations_file (line 30) | def parse_annotations_file(annotation_filename):
method parse_routes_file (line 48) | def parse_routes_file(route_filename, scenario_file, single_route=None):
method parse_weather (line 83) | def parse_weather(route):
method check_trigger_position (line 120) | def check_trigger_position(new_trigger, existing_triggers):
method convert_waypoint_float (line 142) | def convert_waypoint_float(waypoint):
method match_world_location_to_route (line 152) | def match_world_location_to_route(world_location, route_description):
method get_scenario_type (line 182) | def get_scenario_type(scenario, match_position, trajectory):
method scan_route_for_scenarios (line 263) | def scan_route_for_scenarios(route_name, trajectory, world_annotations):
FILE: scenario_runner/srunner/tools/scenario_helper.py
function get_distance_along_route (line 25) | def get_distance_along_route(route, target_location):
function get_crossing_point (line 121) | def get_crossing_point(actor):
function get_geometric_linear_intersection (line 138) | def get_geometric_linear_intersection(ego_actor, other_actor):
function get_location_in_distance (line 172) | def get_location_in_distance(actor, distance):
function get_location_in_distance_from_wp (line 189) | def get_location_in_distance_from_wp(waypoint, distance, stop_at_junctio...
function get_waypoint_in_distance (line 209) | def get_waypoint_in_distance(waypoint, distance):
function generate_target_waypoint_list (line 224) | def generate_target_waypoint_list(waypoint, turn=0):
function generate_target_waypoint_list_multilane (line 259) | def generate_target_waypoint_list_multilane(waypoint, change='left',
function generate_target_waypoint (line 318) | def generate_target_waypoint(waypoint, turn=0):
function generate_target_waypoint_in_route (line 343) | def generate_target_waypoint_in_route(waypoint, route):
function choose_at_junction (line 382) | def choose_at_junction(current_waypoint, next_choices, direction=0):
function get_intersection (line 412) | def get_intersection(ego_actor, other_actor):
function detect_lane_obstacle (line 445) | def detect_lane_obstacle(actor, extension_factor=3, margin=1.02):
class RotatedRectangle (line 483) | class RotatedRectangle(object):
method __init__ (line 489) | def __init__(self, c_x, c_y, width, height, angle):
method get_contour (line 496) | def get_contour(self):
method intersection (line 506) | def intersection(self, other):
FILE: scenario_runner/srunner/tools/scenario_parser.py
class ScenarioConfigurationParser (line 20) | class ScenarioConfigurationParser(object):
method parse_scenario_configuration (line 27) | def parse_scenario_configuration(scenario_name, config_file_name):
method get_list_of_scenarios (line 103) | def get_list_of_scenarios(config_file_name):
Copy disabled (too large)
Download .json
Condensed preview — 392 files, each showing path, character count, and a content snippet. Download the .json file for the full structured content (27,557K chars).
[
{
"path": ".github/FUNDING.yml",
"chars": 818,
"preview": "# These are supported funding model platforms\n\ngithub: [OpenDriveLab] # Replace with up to 4 GitHub Sponsors-enabled use"
},
{
"path": ".gitignore",
"chars": 281,
"preview": "*.log\n*results.json\n*results*.json\n*.pyc\n*.out\nnohup.out\n*.out\nevents*\n*hparams.yaml\nckpt/\n*checkpoints*\n__pycache__\n*wo"
},
{
"path": "LICENSE",
"chars": 11356,
"preview": " Apache License\n Version 2.0, January 2004\n "
},
{
"path": "README.md",
"chars": 5263,
"preview": "> [!IMPORTANT]\n> 🌟 Stay up to date at [opendrivelab.com](https://opendrivelab.com/#news)!\n\n# Think Twice before Driving:"
},
{
"path": "agents/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "agents/navigation/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "agents/navigation/agent.py",
"chars": 9380,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/basic_agent.py",
"chars": 4404,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/behavior_agent.py",
"chars": 19920,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/controller.py",
"chars": 7614,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/global_route_planner.py",
"chars": 18070,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/global_route_planner_dao.py",
"chars": 3129,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/local_planner.py",
"chars": 12251,
"preview": "# Copyright (c) # Copyright (c) 2018-2020 CVC.\n#\n# This work is licensed under the terms of the MIT license.\n# For a cop"
},
{
"path": "agents/navigation/local_planner_behavior.py",
"chars": 7861,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018 Intel Labs.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is li"
},
{
"path": "agents/navigation/roaming_agent.py",
"chars": 2458,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018 Intel Labs.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is li"
},
{
"path": "agents/navigation/types_behavior.py",
"chars": 964,
"preview": "# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource.org/licenses/MIT>.\n\n\"\""
},
{
"path": "agents/tools/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "agents/tools/misc.py",
"chars": 5841,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018 Intel Labs.\n# authors: German Ros (german.ros@intel.com)\n#\n# This work is li"
},
{
"path": "camera_calibration/README.md",
"chars": 2760,
"preview": "# Camera Calibration\n\nUnder the current setting, all four cameras have **fov 150**. If you want to change their fov, you"
},
{
"path": "camera_calibration/calculate_distortion_parameters.py",
"chars": 2821,
"preview": "#!/usr/bin/env python\n\nimport cv2\nimport numpy as np\nimport os\nimport glob\n\n# Defining the dimensions of checkerboard\nCH"
},
{
"path": "camera_calibration/collect_data_for_calibration.py",
"chars": 22687,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2021 IBISC Laborartory, Pelvoux, France\n\n# This work is licensed under the terms "
},
{
"path": "camera_calibration/undistort.py",
"chars": 936,
"preview": "import cv2 as cv\nimport numpy as np\nimport torch\nImageSizeX = 1600\nImageSizeY = 900\nCameraFOV = 150\nf = ImageSizeX /(2 *"
},
{
"path": "dataset/tools/generate_metadata.py",
"chars": 4690,
"preview": "import json\nimport pickle\nimport os, sys\n\ntowns = [\"01\", \"02\", \"03\", \"04\",\"05\", \"06\", \"07\", \"10\"]\nindex_per_down = [\"val"
},
{
"path": "dataset/tools/generate_random_routes.py",
"chars": 17748,
"preview": "import glob\nimport os\nimport sys\nsys.path.append('../../')\n\nimport lxml.etree as ET\nimport argparse\nimport random\nimport"
},
{
"path": "docs/DATA_PREP.md",
"chars": 5108,
"preview": "# Prepare Dataset\n\n## Script to Collect for One Xml File\nDue to the huge size of the dataset (189K frames - 8TB, 2M fram"
},
{
"path": "docs/EVAL.md",
"chars": 2757,
"preview": "# Clsoed-Loop Evaluation\n\nTo evaluate in the town05long:\n```shell\n## In the ThinkTwice/ directory\nport_for_carla=22023 #"
},
{
"path": "docs/INSTALL.md",
"chars": 3796,
"preview": "# Installation\nModified from mmdetection3d, BEVFormer, UniAD\n\n**a. Env: Create a conda virtual environment and activate "
},
{
"path": "docs/TRAIN.md",
"chars": 2577,
"preview": "# Train Your Model\n\n## Script For Training\n\nOur training pipeline is based on [mmcv](https://github.com/open-mmlab/mmcv)"
},
{
"path": "leaderboard/LICENSE",
"chars": 1062,
"preview": "MIT License\n\nCopyright (c) 2019 CARLA\n\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof t"
},
{
"path": "leaderboard/README.md",
"chars": 1487,
"preview": "## Note by ThinkTwice\nWe have changed/added some log related functions of the leaderboard for easier debug. For example,"
},
{
"path": "leaderboard/data/routes_for_evaluation/routes_longest6.xml",
"chars": 196604,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes><route id=\"0\" town=\"Town01\">\n <waypoint pitch=\"0.0\" roll=\"0.0\" x=\"33"
},
{
"path": "leaderboard/data/routes_for_evaluation/routes_town05_long.xml",
"chars": 42615,
"preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<routes>\n <route id=\"16\" town=\"Town05\">\n <waypoint pitch=\"0.0\" roll=\"0.0\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_00.xml",
"chars": 108252,
"preview": "<routes><route id=\"0\" town=\"Town01\">\n <weather cloudiness=\"20.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_01.xml",
"chars": 108310,
"preview": "<routes><route id=\"0\" town=\"Town01\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_02.xml",
"chars": 107929,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"CloudyNight\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_03.xml",
"chars": 107919,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"SoftRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_04.xml",
"chars": 107890,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"HardRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_05.xml",
"chars": 107900,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"HardRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_06.xml",
"chars": 107928,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"MidRainSunset\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_07.xml",
"chars": 107922,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"WetCloudySunset\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_08.xml",
"chars": 107851,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_09.xml",
"chars": 107832,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"SoftRainNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_10.xml",
"chars": 107763,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"CloudyNight\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_11.xml",
"chars": 107939,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"CloudySunset\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town01_val.xml",
"chars": 26997,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town01\">\n <weather id=\"CloudyNoon\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_00.xml",
"chars": 81259,
"preview": "<routes><route id=\"0\" town=\"Town02\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_01.xml",
"chars": 81277,
"preview": "<routes><route id=\"0\" town=\"Town02\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_02.xml",
"chars": 81033,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"ClearSunset\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_03.xml",
"chars": 81098,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"CloudyNight\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_04.xml",
"chars": 81012,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"WetNight\" cloudiness=\"20"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_05.xml",
"chars": 81144,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_06.xml",
"chars": 81097,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"WetCloudyNoon\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_07.xml",
"chars": 81020,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"WetSunset\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_08.xml",
"chars": 81060,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"MidRainyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_09.xml",
"chars": 81101,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"WetCloudyNight\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_10.xml",
"chars": 81145,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"WetSunset\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_11.xml",
"chars": 81010,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town02_val.xml",
"chars": 11369,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town02\">\n <weather id=\"HardRainNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_00.xml",
"chars": 108514,
"preview": "<routes><route id=\"0\" town=\"Town03\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_01.xml",
"chars": 108487,
"preview": "<routes><route id=\"0\" town=\"Town03\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_02.xml",
"chars": 108261,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"CloudySunset\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_03.xml",
"chars": 108177,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"MidRainyNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_04.xml",
"chars": 108146,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"MidRainyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_05.xml",
"chars": 108175,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"WetCloudyNoon\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_06.xml",
"chars": 108234,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"SoftRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_07.xml",
"chars": 108177,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"ClearNight\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_08.xml",
"chars": 108159,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"WetNight\" cloudiness=\"20"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_09.xml",
"chars": 108231,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"MidRainyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_10.xml",
"chars": 108186,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"WetCloudySunset\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_11.xml",
"chars": 108210,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"ClearSunset\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town03_val.xml",
"chars": 27075,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town03\">\n <weather id=\"ClearNight\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_00.xml",
"chars": 114281,
"preview": "<routes><route id=\"0\" town=\"Town04\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_01.xml",
"chars": 114336,
"preview": "<routes><route id=\"0\" town=\"Town04\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_02.xml",
"chars": 113890,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"MidRainSunset\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_03.xml",
"chars": 113882,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"ClearNight\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_04.xml",
"chars": 114026,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"SoftRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_05.xml",
"chars": 113915,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"MidRainyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_06.xml",
"chars": 113909,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"HardRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_07.xml",
"chars": 113906,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"SoftRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_08.xml",
"chars": 113841,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"CloudyNoon\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_09.xml",
"chars": 113905,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"SoftRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_10.xml",
"chars": 113986,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"WetNoon\" cloudiness=\"20."
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_11.xml",
"chars": 113983,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town04_val.xml",
"chars": 32574,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town04\">\n <weather id=\"ClearSunset\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_00.xml",
"chars": 103248,
"preview": "<routes><route id=\"0\" town=\"Town05\">\n <weather cloudiness=\"20.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_01.xml",
"chars": 103188,
"preview": "<routes><route id=\"0\" town=\"Town05\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_02.xml",
"chars": 102830,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"WetCloudySunset\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_03.xml",
"chars": 102770,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"WetNoon\" cloudiness=\"20."
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_04.xml",
"chars": 102787,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"ClearNight\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_05.xml",
"chars": 102883,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"MidRainSunset\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_06.xml",
"chars": 102828,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"ClearNight\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_07.xml",
"chars": 102880,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"HardRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_08.xml",
"chars": 102913,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"HardRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_09.xml",
"chars": 102831,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_10.xml",
"chars": 102914,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"MidRainyNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_11.xml",
"chars": 102795,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"WetSunset\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town05_val.xml",
"chars": 27087,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town05\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_00.xml",
"chars": 81254,
"preview": "<routes><route id=\"0\" town=\"Town06\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_01.xml",
"chars": 81291,
"preview": "<routes><route id=\"0\" town=\"Town06\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_02.xml",
"chars": 81051,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"HardRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_03.xml",
"chars": 81076,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"MidRainyNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_04.xml",
"chars": 80960,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"WetSunset\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_05.xml",
"chars": 81021,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"ClearNoon\" cloudiness=\"1"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_06.xml",
"chars": 81019,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"SoftRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_07.xml",
"chars": 81030,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"SoftRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_08.xml",
"chars": 81040,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"HardRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_09.xml",
"chars": 81012,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"MidRainyNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_10.xml",
"chars": 81054,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"WetCloudyNight\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_11.xml",
"chars": 80956,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"HardRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town06_val.xml",
"chars": 27010,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town06\">\n <weather id=\"ClearSunset\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_00.xml",
"chars": 81572,
"preview": "<routes><route id=\"0\" town=\"Town07\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_01.xml",
"chars": 81540,
"preview": "<routes><route id=\"0\" town=\"Town07\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000\" "
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_02.xml",
"chars": 81289,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"SoftRainSunset\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_03.xml",
"chars": 81264,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"SoftRainNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_04.xml",
"chars": 81187,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"WetCloudyNoon\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_05.xml",
"chars": 81252,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"HardRainNight\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_06.xml",
"chars": 81296,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"CloudySunset\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_07.xml",
"chars": 81237,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"WetSunset\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_08.xml",
"chars": 81263,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"MidRainSunset\" cloudines"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_09.xml",
"chars": 81205,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"CloudyNoon\" cloudiness=\""
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_10.xml",
"chars": 81203,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"SoftRainNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_11.xml",
"chars": 81363,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"MidRainyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town07_val.xml",
"chars": 27097,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town07\">\n <weather id=\"WetCloudyNight\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_00.xml",
"chars": 101865,
"preview": "<routes><route id=\"0\" town=\"Town10HD\">\n <weather cloudiness=\"80.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_01.xml",
"chars": 102329,
"preview": "<routes><route id=\"0\" town=\"Town10HD\">\n <weather cloudiness=\"90.000000\" fog_density=\"0.000000\" fog_distance=\"0.000000"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_02.xml",
"chars": 103000,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"WetSunset\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_03.xml",
"chars": 103031,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"WetNoon\" cloudiness=\"2"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_04.xml",
"chars": 103098,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"MidRainyNight\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_05.xml",
"chars": 103067,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"MidRainyNight\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_06.xml",
"chars": 103076,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"MidRainyNight\" cloudin"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_07.xml",
"chars": 103052,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"ClearNoon\" cloudiness="
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_08.xml",
"chars": 103119,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"CloudyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_09.xml",
"chars": 103063,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"CloudyNoon\" cloudiness"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_10.xml",
"chars": 102961,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"MidRainyNoon\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_11.xml",
"chars": 103093,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"HardRainNoon\" cloudine"
},
{
"path": "leaderboard/data/routes_for_open_loop_training/routes_town10_val.xml",
"chars": 27163,
"preview": "<?xml version='1.0' encoding='UTF-8'?>\n<routes>\n <route id=\"0\" town=\"Town10HD\">\n <weather id=\"SoftRainSunset\" cloudi"
},
{
"path": "leaderboard/data/scenarios/all_towns_traffic_scenarios_no256.json",
"chars": 4465253,
"preview": "{\r\n \"available_scenarios\": [\r\n {\r\n \"Town01\": [\r\n {\r\n \"available_e"
},
{
"path": "leaderboard/data/scenarios/longest6_eval_scenarios.json",
"chars": 4372244,
"preview": "{\n \"available_scenarios\": [\n {\n \"Town01\": [\n {\n \"available_event_"
},
{
"path": "leaderboard/leaderboard/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/autoagents/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/autoagents/agent_wrapper.py",
"chars": 13844,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT licen"
},
{
"path": "leaderboard/leaderboard/autoagents/autonomous_agent.py",
"chars": 3873,
"preview": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource"
},
{
"path": "leaderboard/leaderboard/autoagents/dummy_agent.py",
"chars": 3303,
"preview": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource"
},
{
"path": "leaderboard/leaderboard/autoagents/human_agent.py",
"chars": 8281,
"preview": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource"
},
{
"path": "leaderboard/leaderboard/autoagents/human_agent_config.txt",
"chars": 526,
"preview": "mode: log # Either 'log' or 'playback'\nfile: test.json # path to the file with "
},
{
"path": "leaderboard/leaderboard/autoagents/npc_agent.py",
"chars": 3323,
"preview": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource"
},
{
"path": "leaderboard/leaderboard/autoagents/ros_agent.py",
"chars": 18482,
"preview": "#!/usr/bin/env python\n#\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT lice"
},
{
"path": "leaderboard/leaderboard/envs/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/envs/sensor_interface.py",
"chars": 8991,
"preview": "import copy\nimport logging\nimport numpy as np\nimport os\nimport time\nfrom threading import Thread\n\nfrom queue import Queu"
},
{
"path": "leaderboard/leaderboard/leaderboard_evaluator.py",
"chars": 21970,
"preview": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Corporation.\n# authors: German Ros (german.ros@intel.com), Felipe "
},
{
"path": "leaderboard/leaderboard/scenarios/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/scenarios/background_activity.py",
"chars": 3390,
"preview": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensour"
},
{
"path": "leaderboard/leaderboard/scenarios/master_scenario.py",
"chars": 4435,
"preview": "#!/usr/bin/env python\n\n#\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensour"
},
{
"path": "leaderboard/leaderboard/scenarios/route_scenario.py",
"chars": 25545,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT licen"
},
{
"path": "leaderboard/leaderboard/scenarios/scenario_manager.py",
"chars": 7502,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT "
},
{
"path": "leaderboard/leaderboard/scenarios/scenarioatomics/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/scenarios/scenarioatomics/atomic_criteria.py",
"chars": 4023,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2020 Intel Corporation\n#\n# This work is licensed under the terms of the MIT "
},
{
"path": "leaderboard/leaderboard/utils/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "leaderboard/leaderboard/utils/checkpoint_tools.py",
"chars": 2031,
"preview": "import json\ntry:\n import simplejson as json\nexcept ImportError:\n import json\nimport requests\nimport os.path\n\n\ndef "
},
{
"path": "leaderboard/leaderboard/utils/result_writer.py",
"chars": 4110,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT "
},
{
"path": "leaderboard/leaderboard/utils/route_indexer.py",
"chars": 2523,
"preview": "from collections import OrderedDict\nfrom dictor import dictor\n\nimport copy\n\nfrom srunner.scenarioconfigs.route_scenario_"
},
{
"path": "leaderboard/leaderboard/utils/route_manipulation.py",
"chars": 5407,
"preview": "#!/usr/bin/env python\n# Copyright (c) 2018-2019 Intel Labs.\n# authors: German Ros (german.ros@intel.com), Felipe Codevil"
},
{
"path": "leaderboard/leaderboard/utils/route_parser.py",
"chars": 15119,
"preview": "#!/usr/bin/env python\n\n# This work is licensed under the terms of the MIT license.\n# For a copy, see <https://opensource"
},
{
"path": "leaderboard/leaderboard/utils/statistics_manager.py",
"chars": 13845,
"preview": "#!/usr/bin/env python\n\n# Copyright (c) 2018-2019 Intel Corporation\n#\n# This work is licensed under the terms of the MIT "
},
{
"path": "leaderboard/scripts/collect_data.sh",
"chars": 1476,
"preview": "#!/bin/bash\nexport CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI\nexport P"
},
{
"path": "leaderboard/scripts/evaluation_longest6.sh",
"chars": 1512,
"preview": "#!/bin/bash\nexport CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI\nexport P"
},
{
"path": "leaderboard/scripts/evaluation_town05long.sh",
"chars": 1517,
"preview": "#!/bin/bash\nexport CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh\nexport PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI\nexport P"
},
{
"path": "leaderboard/team_code/auto_pilot.py",
"chars": 13276,
"preview": "import os\nimport time\nimport datetime\nimport pathlib\nimport json\nimport random\n\nimport numpy as np\nimport cv2\nimport car"
},
{
"path": "leaderboard/team_code/base_agent.py",
"chars": 36367,
"preview": "import time\nimport os\nimport datetime\nimport pathlib\nimport json\n\nimport cv2\nimport carla\n\nfrom leaderboard.autoagents i"
},
{
"path": "leaderboard/team_code/map_agent.py",
"chars": 5592,
"preview": "import numpy as np\nfrom PIL import Image, ImageDraw\n\nfrom srunner.scenariomanager.carla_data_provider import CarlaDataPr"
},
{
"path": "leaderboard/team_code/pid_controller.py",
"chars": 763,
"preview": "from collections import deque\n\nimport numpy as np\n\n\nclass PIDController(object):\n def __init__(self, K_P=1.0, K_I=0.0"
},
{
"path": "leaderboard/team_code/planner.py",
"chars": 3496,
"preview": "import os\nfrom collections import deque\n\nimport numpy as np\n\n\nDEBUG = int(os.environ.get('HAS_DISPLAY', 0))\n\n\nclass Plot"
},
{
"path": "leaderboard/team_code/roach_ap_agent_data_collection.py",
"chars": 41780,
"preview": "import os\nimport carla\n\nimport json\nimport datetime\nimport pathlib\nimport time\nimport cv2\nfrom collections import deque\n"
},
{
"path": "leaderboard/team_code/thinktwice_agent.py",
"chars": 23516,
"preview": "import os\nimport json\nimport datetime\nimport pathlib\nfrom select import select\nimport time\nfrom unittest import result\ni"
},
{
"path": "leaderboard/team_code/thinktwice_agent_old.py",
"chars": 23424,
"preview": "import os\nimport json\nimport datetime\nimport pathlib\nfrom select import select\nimport time\nfrom unittest import result\ni"
},
{
"path": "open_loop_training/__init__.py",
"chars": 0,
"preview": ""
},
{
"path": "open_loop_training/code/__init__.py",
"chars": 185,
"preview": "from .datasets.pipelines import *\nfrom .datasets import CarlaDataset\nfrom .model_code.backbones import *\nfrom .model_cod"
},
{
"path": "open_loop_training/code/apis/__init__.py",
"chars": 143,
"preview": "from .train import custom_train_model\nfrom .mmdet_train import custom_train_detector\n__all__ = ['custom_train_model', 'c"
},
{
"path": "open_loop_training/code/apis/mmdet_train.py",
"chars": 7964,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "open_loop_training/code/apis/train.py",
"chars": 1915,
"preview": "# ---------------------------------------------\n# Copyright (c) OpenMMLab. All rights reserved.\n# ----------------------"
},
{
"path": "open_loop_training/code/core/evaluation/__init__.py",
"chars": 101,
"preview": "from .eval_hooks import CustomDistEvalHook, CustomEvalHook\nfrom .epoch_hook import MySetEpochInfoHook"
},
{
"path": "open_loop_training/code/core/evaluation/epoch_hook.py",
"chars": 394,
"preview": "from mmcv.parallel import is_module_wrapper\nfrom mmcv.runner import HOOKS, Hook\n\n\n@HOOKS.register_module()\nclass MySetEp"
},
{
"path": "open_loop_training/code/core/evaluation/eval_hooks.py",
"chars": 6177,
"preview": "\n# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,\n# in order to avoid strong version dependenc"
},
{
"path": "open_loop_training/code/core/evaluation/eval_tool.py",
"chars": 5865,
"preview": "# ---------------------------------------------\r\n# Copyright (c) OpenMMLab. All rights reserved.\r\n# --------------------"
},
{
"path": "open_loop_training/code/datasets/__init__.py",
"chars": 115,
"preview": "from .carla_dataset import CarlaDataset\nfrom .builder import custom_build_dataset\n\n__all__ = [\n \"CarlaDataset\"\n]\n"
},
{
"path": "open_loop_training/code/datasets/base_dataset.py",
"chars": 2057,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport warnings\nimport os.path as osp\nfrom abc import ABCMet"
},
{
"path": "open_loop_training/code/datasets/builder.py",
"chars": 5921,
"preview": "\n# Copyright (c) OpenMMLab. All rights reserved.\nimport copy\nimport platform\nimport random\nfrom functools import partial"
},
{
"path": "open_loop_training/code/datasets/carla_dataset.py",
"chars": 15563,
"preview": "import os\nfrom unittest import result\nimport cv2\nimport copy\nimport mmcv\nimport torch\nimport random\nimport numpy as np\nf"
},
{
"path": "open_loop_training/code/datasets/pipelines/__init__.py",
"chars": 384,
"preview": "from .transform import (InitMultiImage, ImageTransformMulti, IDAImageTransform)\nfrom .loading import LoadMultiImages, Lo"
},
{
"path": "open_loop_training/code/datasets/pipelines/formating.py",
"chars": 2572,
"preview": "\r\n# Copyright (c) OpenMMLab. All rights reserved.\r\nimport torch\r\nimport numpy as np\r\nfrom mmcv.parallel import DataConta"
},
{
"path": "open_loop_training/code/datasets/pipelines/loading.py",
"chars": 6709,
"preview": "# Copyright (c) OpenMMLab. All rights reserved.\nimport os\nfrom types import new_class\nimport cv2\nimport time\nimport copy"
},
{
"path": "open_loop_training/code/datasets/pipelines/transform.py",
"chars": 19167,
"preview": "from email.mime import image\nimport os\nimport cv2\nimport copy\nimport numpy as np\nfrom numpy import random\nimport matplot"
},
{
"path": "open_loop_training/code/datasets/samplers/__init__.py",
"chars": 148,
"preview": "from .group_sampler import DistributedGroupSampler\nfrom .distributed_sampler import DistributedSampler\nfrom .sampler imp"
},
{
"path": "open_loop_training/code/datasets/samplers/distributed_sampler.py",
"chars": 1371,
"preview": "import math\n\nimport torch\nfrom torch.utils.data import DistributedSampler as _DistributedSampler\nfrom .sampler import SA"
},
{
"path": "open_loop_training/code/datasets/samplers/group_sampler.py",
"chars": 3735,
"preview": "\n# Copyright (c) OpenMMLab. All rights reserved.\nimport math\n\nimport numpy as np\nimport torch\nfrom mmcv.runner import ge"
},
{
"path": "open_loop_training/code/datasets/samplers/sampler.py",
"chars": 189,
"preview": "from mmcv.utils.registry import Registry, build_from_cfg\r\n\r\nSAMPLER = Registry('sampler')\r\n\r\n\r\ndef build_sampler(cfg, de"
},
{
"path": "open_loop_training/code/encoder_decoder_framework.py",
"chars": 21812,
"preview": "from collections import deque, OrderedDict\nfrom distutils.command.config import config\nimport cv2\nimport numpy as np\nimp"
},
{
"path": "open_loop_training/code/model_code/backbones/__init__.py",
"chars": 150,
"preview": "\nfrom .lidarnet import LidarNet, SparseEncoder_fp32\nfrom .lss import LSS, PAFPN_fp32\n__all__ = ['LidarNet', 'LSS', \"Spar"
},
{
"path": "open_loop_training/code/model_code/backbones/lidarnet.py",
"chars": 3389,
"preview": "import copy\r\nimport numpy as np\r\n\r\nimport torch\r\nimport torch.nn as nn\r\nimport torch.nn.functional as F\r\nfrom torch.dist"
},
{
"path": "open_loop_training/code/model_code/backbones/lss.py",
"chars": 28567,
"preview": "## Copyright (c) Megvii Inc. All rights reserved.\n## From BEVDepth\n## Modified by Xiaosong Jia\nimport torch\nimport torch"
}
]
// ... and 192 more files (download for full content)
About this extraction
This page contains the full source code of the OpenDriveLab/ThinkTwice GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 392 files (24.2 MB), approximately 6.4M tokens, and a symbol index with 1799 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.
Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.