From bf574bf9d54c2ba2f3cce1ebbb48f07be1b658f6 Mon Sep 17 00:00:00 2001 From: klemense1 Date: Fri, 9 Jul 2021 10:41:24 +0200 Subject: [PATCH] initial commit --- .bazelrc | 6 + .github/workflows/CI.yml | 21 + README.md | 61 + WORKSPACE | 35 + benchmark_results.png | Bin 0 -> 13466 bytes results/BUILD | 0 results/benchmark/BUILD | 5 + results/benchmark/benchmark_results.zip | 3 + src/BUILD | 0 src/common/BUILD | 6 + src/common/custom_lane_corridor_config.py | 81 + src/create_figures/BUILD | 17 + .../plot_benchmark_results.ipynb | 1617 +++++++++++++++++ src/create_figures/run_notebooks.py | 7 + src/database/BUILD | 10 + src/database/maps/merging_long_v01.xodr | 178 ++ .../scenario_sets/merging_light_dense.json | 211 +++ .../scenario_sets/merging_mid_dense.json | 211 +++ src/mcts_config/BUILD | 48 + .../mcts_behavior_config_reader.py | 92 + src/mcts_config/mcts_config.py | 48 + src/mcts_config/mcts_config_test.py | 46 + src/mcts_config/params/BUILD | 5 + src/mcts_config/params/common.json | 254 +++ src/mcts_config/params/mobil.json | 39 + src/mcts_config/params/sa_lex_mcts_sd.json | 104 ++ src/mcts_config/params/sa_mcts.json | 74 + src/run/BUILD | 76 + src/run/merging_test_random.py | 92 + src/run/merging_test_specific.py | 88 + src/run/run_benchmark.py | 106 ++ src/run/scenario_tuning.py | 84 + src/traffic_rules/BUILD | 7 + src/traffic_rules/rule_generation.py | 72 + src/traffic_rules/traffic_rules_evaluators.py | 68 + src/viewer_config/BUILD | 17 + src/viewer_config/params/BUILD | 5 + .../params/mp_viewer_description.json | 48 + .../params/mp_viewer_params.json | 84 + src/viewer_config/viewer_config.py | 13 + src/viewer_config/viewer_config_test.py | 19 + tools/BUILD | 0 tools/deps.bzl | 28 + tools/python/BUILD | 1 + tools/python/into_venv.sh | 3 + tools/python/requirements.txt | 22 + tools/python/setup_venv.sh | 5 + 47 files changed, 4017 insertions(+) create mode 100644 .bazelrc create mode 100644 .github/workflows/CI.yml create mode 100644 README.md create mode 100644 WORKSPACE create mode 100644 benchmark_results.png create mode 100644 results/BUILD create mode 100644 results/benchmark/BUILD create mode 100644 results/benchmark/benchmark_results.zip create mode 100644 src/BUILD create mode 100644 src/common/BUILD create mode 100644 src/common/custom_lane_corridor_config.py create mode 100644 src/create_figures/BUILD create mode 100644 src/create_figures/plot_benchmark_results.ipynb create mode 100644 src/create_figures/run_notebooks.py create mode 100644 src/database/BUILD create mode 100644 src/database/maps/merging_long_v01.xodr create mode 100644 src/database/scenario_sets/merging_light_dense.json create mode 100644 src/database/scenario_sets/merging_mid_dense.json create mode 100644 src/mcts_config/BUILD create mode 100644 src/mcts_config/mcts_behavior_config_reader.py create mode 100644 src/mcts_config/mcts_config.py create mode 100644 src/mcts_config/mcts_config_test.py create mode 100644 src/mcts_config/params/BUILD create mode 100644 src/mcts_config/params/common.json create mode 100644 src/mcts_config/params/mobil.json create mode 100644 src/mcts_config/params/sa_lex_mcts_sd.json create mode 100644 src/mcts_config/params/sa_mcts.json create mode 100644 src/run/BUILD create mode 100644 src/run/merging_test_random.py create mode 100644 src/run/merging_test_specific.py create mode 100644 src/run/run_benchmark.py create mode 100644 src/run/scenario_tuning.py create mode 100644 src/traffic_rules/BUILD create mode 100644 src/traffic_rules/rule_generation.py create mode 100644 src/traffic_rules/traffic_rules_evaluators.py create mode 100644 src/viewer_config/BUILD create mode 100644 src/viewer_config/params/BUILD create mode 100644 src/viewer_config/params/mp_viewer_description.json create mode 100644 src/viewer_config/params/mp_viewer_params.json create mode 100644 src/viewer_config/viewer_config.py create mode 100644 src/viewer_config/viewer_config_test.py create mode 100644 tools/BUILD create mode 100644 tools/deps.bzl create mode 100644 tools/python/BUILD create mode 100644 tools/python/into_venv.sh create mode 100644 tools/python/requirements.txt create mode 100644 tools/python/setup_venv.sh diff --git a/.bazelrc b/.bazelrc new file mode 100644 index 0000000..5e02a80 --- /dev/null +++ b/.bazelrc @@ -0,0 +1,6 @@ +test --test_output=errors --action_env="GTEST_COLOR=1" + +# Force bazel output to use colors (good for jenkins) and print useful errors. +common --color=yes + +build --cxxopt='-std=c++17' --define planner_rules_mcts=true --define ltl_rules=true diff --git a/.github/workflows/CI.yml b/.github/workflows/CI.yml new file mode 100644 index 0000000..b3803a9 --- /dev/null +++ b/.github/workflows/CI.yml @@ -0,0 +1,21 @@ +name: CI + +on: + push: + schedule: + - cron: "0 2 * * *" + +jobs: + build: + + runs-on: ubuntu-latest + container: + image: docker://barksim/bark:latest + steps: + - uses: actions/checkout@v1 + - name: Setting up virtual environment + run: virtualenv -p python3 ./tools/python/venv --system-site-packages + - name: Getting into venv + run: . ./tools/python/venv/bin/activate + - name: Runing merging_test_specific + run: bazel test //src/run:merging_test_specific \ No newline at end of file diff --git a/README.md b/README.md new file mode 100644 index 0000000..1bb4445 --- /dev/null +++ b/README.md @@ -0,0 +1,61 @@ +# Example Benchmark + +Repository showing how to use BARK for research, e.g., conducting reproducible experiments. The core of this example repository is to run a benchmark of a single agent Monte Carlo Tree Search and compare it with MCTS variants, that incorporate penalties for violating traffic rules to their reward function. The study focuses on merging -- an arbitrary number of scenarios can be generated, where the initial positions and velocities of the vehicles are sampled randomly from a normal distribution. + +## Getting started: +If you are not familar with BARK yet, check out our BARK paper [paper](https://arxiv.org/abs/2003.02604) and the code documentation [documentation](https://bark-simulator.readthedocs.io/en/latest/). +This repository uses a virtual environment just as BARK does (install via `bash tools/python/setup_venv.sh` and then source it via `source tools/python/into_venv.sh`) + +## What is in there: +There are three targets ready for execution +* `merging_test_random`: runs N scenarios and sample the initial states randomly +* `merging_test_specific`: runs a specific scenario (you can tune them) +* `run_benchmark`: runs a full benchmark +* `scenario_tuning`: runs a lightweight benchmark with visualization to find suitable scenario generation parameters + +## Benchmark +First, execute `bazel run //src/run:run_benchmark`. The results of the benchmark will be saved at +`example_benchmark/bazel-bin/src/run/run_benchmark.runfiles/example_benchmark`. Copy the file to `results/benchmark`. The result file consists of a pandas dataframe, that represents the outcome of each benchmark simulation run. To visualize that, we have prepared an ipython notebook. You can start the notebook server via `bazel run //src/create_figures:run_notebooks` and then select the `plot_benchmark_results` notebook. The code will generate the following figure: + +![Benchmark Results](benchmark_results.png) + +### Changing Parameters: +Parametrization in BARK is done via the `ParameterServer`, which reads json-files. You can tweak the existing ones: +* for the viewer in `viewer_config/params/` +* for the behavior models in `mcts_config/params/` + +Of course, those json-files are quite nested, so we provide scripts to generate them with default values. +* for the viewer: `src/viewer_config/viewer_config_test.py` +* for the behavior models: `src/mcts_config/mcts_config_test.py` +The concept for creating parameter files can be transferred to any other object. + +### Evaluators: +Evaluators can be used as a metric to analyze the benchmark, but also as a termination criterion for a simulation run. You can choose from any Evaluator in https://github.com/bark-simulator/bark/tree/master/bark/world/evaluation. Using EvaluatorLTL for example allows you to use a wide range of traffic rules. + +### Scenarios: +The scenarios are generated based on the config files in `src/database/scenario_sets`. + +## Dependency Management using Bazel +As you can see in the [bark-simulator Github Group](https://github.com/bark-simulator/), the BARK ecosystem is split over multiple Github repositories. One reason for this was to keep the core functionalities light-weight and reasonably fast to build. Specifically, a lot of planning modules are placed in seperate repositories. Using Bazel as our build environment enables the reproducibility of our experiments, as dependency versions of the repositories can be tracked easily. + +For example, have a look to `tools/deps.bzl`, where the specific dependencies and either their commit hashs or a specific branch can be selected. In order to try two different versions of your planner (located in another repo), you do not build or install them manually, you just need to change the commit hash. + +## Cite us + +This repository contains work from multiple publications: +* Traffic Rules as Evaluators: [Formalizing Traffic Rules for Machine Interpretability](https://arxiv.org/abs/2007.00330) +* MCTS with Traffic Rules: [Modeling and Testing Multi-Agent Traffic Rules within Interactive Behavior Planning](https://arxiv.org/abs/2009.14186) + +If you use them, please cite them. + +For everything else, please cite us using the following [paper](https://arxiv.org/abs/2003.02604): + +``` +@inproceedings{Bernhard2020, + title = {BARK: Open Behavior Benchmarking in Multi-Agent Environments}, + author = {Bernhard, Julian and Esterle, Klemens and Hart, Patrick and Kessler, Tobias}, + booktitle = {2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, + url = {https://arxiv.org/pdf/2003.02604.pdf}, + year = {2020} +} +``` \ No newline at end of file diff --git a/WORKSPACE b/WORKSPACE new file mode 100644 index 0000000..fdc0687 --- /dev/null +++ b/WORKSPACE @@ -0,0 +1,35 @@ +workspace(name = "example_benchmark") + +load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive", "http_file") +load("@bazel_tools//tools/build_defs/repo:git.bzl", "git_repository") +load("//tools:deps.bzl", "example_benchmark_dependencies") + +example_benchmark_dependencies() + +load("@bark_project//tools:deps.bzl", "bark_dependencies") +bark_dependencies() + +load("@com_github_nelhage_rules_boost//:boost/boost.bzl", "boost_deps") +boost_deps() + +# -------- Benchmark Database ----------------------- +git_repository( + name = "benchmark_database", + commit = "422b0ddd316ab46ac79dcd72a45645e197cf7da1", + remote = "https://github.com/bark-simulator/benchmark-database", +) + +load("@benchmark_database//util:deps.bzl", "benchmark_database_dependencies") +benchmark_database_dependencies() + +load("@benchmark_database//load:load.bzl", "benchmark_database_release") +benchmark_database_release() + +load("@rule_monitor_project//util:deps.bzl", "rule_monitor_dependencies") +rule_monitor_dependencies() + +load("@planner_rules_mcts//util:deps.bzl", "planner_rules_mcts_dependencies") +planner_rules_mcts_dependencies() + +load("@pybind11_bazel//:python_configure.bzl", "python_configure") +python_configure(name = "local_config_python") \ No newline at end of file diff --git a/benchmark_results.png b/benchmark_results.png new file mode 100644 index 0000000000000000000000000000000000000000..5239903f42d998122e850cbb25063ab3c0dc2e97 GIT binary patch literal 13466 zcmd^mc|6r?`}L;rC^-#O3a6q>QJEq`CDkTE+mKmhE@X@{oW|22wKGJ8%rk{dnQ}@Q z%NRnFaT`N2|JL1f&htFy`MvMw{rCOjbUv~7_j?c5wXU_+b#+-?Z67NOCkur_VWsZh zqe-DK>ryC8Hx|yvPaGt;Z{vT`PD;8?hwRLqTumL!D5|DT_Q&m*7Rj}#Zj zXZR;)Fn&)I7Sq%m`t_Lg0wJM<(7oN}f~QRO?5?g|Q8YgNPNq$Fh|*dtSI8JY_2rN3 zT4Y$*Z)qw_lrZHNRaJp0DJhb6t;byi{G;{eCieCo=i}v# zO-)s2VqyxG_sG#pw>(*SQYAq6)ztW~^Tdc%i$mGwiRQMMjXXR&9^>tSoLi5a50*U9 zBO@sxq2=l6ncT4HUL(>zZqt7?^cD1;+)xEs0$VXMZBUyKaU8r)$zH{?g zd8v&0B*(TjSUhJ>V_HljA1z0)U_nAy*v`X;5BD^rgz~3jt>XbMt8T zk*@pL@L^#N*45kgBxomXi#SH1s8?u>d$-$fU$J5ZZ^CH#)9qKEuD??e{pQUZ$Lot& zS)KEiu(J9Wzq8M4O|$TwzhrG}SC{2xz4TazD+?%;I?W8-^^XlqO-(00-a6>?lwGF_ zZzKnioIhc$v}ez4Lrw}M_H6tVyD%O)HFbu4 zsg1iepOurBI`Q@#Tl%S?BW|ZpCqzc>$vZu!?c|hhHGq?#o#3!g&E2Xr@80wkflL5F z*ct2h7MA|T>*rD^gW_|Av4?X@Q}O5Gy@klsEvuLoQ7DBbfB!{Cz#1Qpl`DnhK-+Myjk(5t!=nH(>aIX5vT#9g_~W9(jzGb4Ipl#zRsK%8%TfOm#z@q9CL^LV2? z_x@Gfcx*(r8Jji&$SgzqYROu>&hL)C=F2&3vSAO7mh{}*$E{&vViK2+UFRHCCJ%WR z;O+0{haL8&RVioa3v--kepJDA2;V%l7;o-t&dfau`0y4iN*XH?6cMTaea-@!fkAI2 zc1n@GqR(9aDq`R0pUV$+JzHZ(8|!az{@^3k^I}tIEq>mzl?z|pcT%M=SjIUX+luxV z(y_*MC?7o7F!Z5B!nud$dH{#`R^!dX1&o@53R-*jUSwuw=A~BLk!rZMTI^V6^N)v= zu?yST+1zIaN! zn7MwX@tOM~hB^D`lD2P7wSKV8?URg%Cbzr);=IJTLowEM@mlnm0S)QdvLg>HTXLND zs{VpK-CVp#*P_^;H_5o5HP)2e<=RYn!Oldav(<1%h5uG|98UL}WvLfg*F@XpkME_6 z+qKI2tQOmQ^x3snkKKmf{5-yi?wHWpWWycQYC50F2u_+GNHg$w`1+6CWvePush5R0 zu72)qj5rjd7N?bYj?yx-vC~Zu@+ZyM&B3mVEa9_m_{YqJh{`K{doI7%%kj-uKTk} zy*OZDO?CAOF0Rc~WmQ$Vfs=r#ZPs7I>zHmKV9tJCqC%_Fh_5imA`<+x(>S;B;m%x7 z&*2IwA5Ijhu+pu^Z=KfAc*Qq;@)8i3m0MQVCD-uPt5;1Aj_wO8*?jon9@jRHO!v{A zsF+Ysy%@E7Ig#=>zfW6wS+q}`$`a-%bDPBSa0HJ|G@IA@i2#4ET)wP9qxo&yw$1Ox zjj;6ebj_09mRy}Q^NQ++W@WSjPY=0I&o{VZml950FBg5r9r*>CGLe?my;y4u*6#=~>O^AJUBb-JFkJr>$mGc&P zgHIOy6+Ng3V%D(^5AfBhDxH%jA0%og{2fB8LgaoxXs#tn%}%$~9H}!C4F#MMwCuS* zG4slmE1D<+XV0Be+03SF@!6b|fr!06ngEInpqkR&y+-M5xP-@VKBZbvn=)(ywUhLs z9zT|yw_pJy1dPNRpX$uu5x;FR#*IZlOVs*Ac@F*DwY607IWO1Mm5Y3h#bSq)p; zxs3f=?;pwVi*AFV>%G>~19_S!gtQawo4E-HAABFc_k5~(l6Q`ePo6{4Y@I42%ikkp}c9U3W zd>EDd_>=M|qoJy94A=!KaWKQWZkxl`$UoY}o#^Mc0)ZP@p3kQe&{d~nEa4!7h4>z` zEOeip9vekb31}QEoWo{0+Ecezjo{$T#jLt+Zf>2ja|RP{-1xP1Iocnd`DEZID?;S-$(49ckLuJV>FeO^>wq}5 zStpPFcxszvI!dH_e|G0J?yre!kK4s#thfCq*(^_D5(3f^;GOu~mvD*4Q+J0;uYKoN z#3@Q*vZ;=w_O#~ZnpcG+*|y|Z^}c@4e|HJW*oIY{se64mwR$w9_g!DBkz$lrn{IWe z#ks+7qCL>~+PBZFcIQdV%G&P3EvM%(F`{w&cp{2+_#b~PY&%pmXru>+olOT)F{5l zDq;I(JNU^eIfB>wa1po_tC^|srd-#Qn&r_?a*EAU~_V-x3{KM2*&yURThX%>7V!S9_g+j zwOfAX%Te&hr%#`D=TG(v4Zr>mmdub`Cg(nK!`Ih$YHEs?x?$h-j}MUjVNc?n3Q4)I zQkYFd+)aOOw&UDxA0`77>6p%>)9EXgFOP_g7V*xEdjG?C zKx}mU$g+3A5;pkU2Go2KmbmU$@mdL$(#ikGdgFTOOq89h>QQq7ir=a4-~R{0+0rr= zxEoY5Z{EBY)^d(Tl}8>tH%}9gl4@`+|1$K!xk_%VD=sFa`o7|&H^#Df>mynB%l0qB zc9m9Eilo_%e`>#2F5^kV>5HsH1NNW_@{ zcyPhYM8eecw8V)f@r>h*npj3%tVRS)Q*%Alx;FOaMzy=K$VC6(1Q0_(0Re$wmemx> zc7;pD>u?z!fHCtxO)K1S`~jqxx`xKhvuDqii_8OKE&d<+pdhC|g7)9g!1`qKg z-@tg!f8)acLXx?sg?Ar(;!NRKzQ5*LgPBSI?`6OL~uv$6-m?O=)Rq5~l`D zP^6Xi?XxMl&J|eeTL0qKCM^R41Azf#SWjeDmM#>TcnTep%D3F^6Q*)qR?0GC(!X`JGgzjc?3En%V*Mlrt2EWAD8XvuZ!*Qus)kItTD zMheCm7kJVu&!>V+@o(DHdDa8hz^>89tbG_d2PbhXBP83z;(;zu#_!IZ(?z5nUWs*4 zIUjQT&E%pA5hnkx3-S-5D?A3r+toESeAJ+zpzq2^lnRio1JkbidgjV;Mo`c*sq^&$=t*bCB6wReN7O9G&QyB>o;rw97y%G z6}0tMlNUWb8ltp{lQSMNLvYikefM^_20T6T3Yl^&!~MWzd?N7Aqt#`%4$33f-IWoX z?(P0Myi_6*fsKE?W=DUP;uM`jncOgN(5@FR5H{ zgpk9~ZExq!d#(^|9()SSmkiHk6y@nKO@noMdm&r=cMYxGczQQ2cd<9;0>1d4xl1T`n;w zYRWnpVdItx`HZCz-YY-ZEB4ppZ*4jlP*C6%C+X$og~NOic?Dk-e0G#s+tYJKx{7Nt zj0j{Xm7S#HHH7EOm+Bx^QMBfO&H70B1Mv$H6h~yuZ%q!qD<18N@U{Lj_%5d-*e2bg zihHwe>P}y|&$oZ9b#5Zloca8}{kD?`y8sbGK^P~Ik-UWUm65(E+${VMXV$@TY z5ZFl4#()DMDFM}pnx8>y2EO~#=|?n`@GEwbQSY8yux@?q7Wc@!BDmW}s&z};dICU0 zxA~rghp&fhO`zRD=&9Y^Zu)xdzm;#=o;~Lurlt8qIYCE)09j6qbd&rv9cHF@2R}tl zqfVtjXj&C|GbKNgu&M9LVI+$=g?umHQBD6;-7i)`0a`D?WIUSo`A&ExKgMgXPBFM35YZ z-$w@tKoTX^iyf}{S@vJLk*fV}s}4@owD{r`UtibeFLrsO0k998dTIqK?n)n8zVX0I z@V7UTkXErlNNv828$&YfAbc*CFI~25J(a|kfx%s5?s3UGpN5A~a)cA=1Y>FhE)~C% zA?*0Etoh|s&*_P%nf=vpZ)mwLClsG4cur+qUn~9IJV}F@9)3=&a!CHA$Rv2 zUI8(&LvSW~3jjFm9a!EopEa&(&6#bU2@S?xEjNZ1v9J(_0u_Eg9d<|LYBBTubR>rV z?c1^0j-91#ZEdMS=6JRFr`z6I0RYSHv?_VAV~Kc>4S0;%XI#{QxVX5B<;bG92ojh! zQAVKMc% zn62)<;(`VSqDBw|kRYa5m23p0U*n%W_*7}th_{xmZr4Qg+sb=8wA9rBSo5j$`HNTC zS7t6k=E>gcX8MXDfVW67DGrhguw?kCG9DA@jAvnZhSmjq1k}d8Bglf#sCkPxy83em zTt-i{rZnc+>$mvqN;~B#aZR9aS6^TAgkIp1Tl z=iMcqdeo9~5m-iH2C^b11hrdoT^o8E(@1fHXs++2lXG}F;w^!jhx*7i;*oaPgXqzO zFb6!icH^|RK7hFN{v_tXrj3}~>&u;l>*JS{)KSOd9?5Oo=7P5ScXRGJE|h<|0x z9BpJry5+0&1c?+cEzvr1BwRaD_x|0xYayXPm4gfc7dx|WbEopYu+9*amp8h3^Jefi zvn!mE$77)a1%CUj@LS=n81eQG42*%PV>8g2m(!oa5I_2CvB%KUm7u;g06#a5bvPe~ z18pDW&C6HS#U0uQWpyhsFc6_@1{>G@-EJV~1)Lc1f~HweP;y6_Y*OM7z=*wj7ng7e zQa_E2>0phI?AmM{F5pPokGdE3v=tPDhlj7=;D}C46o#`AN%MlmeITCH<0A*ybiqVw z0gM@TZSp>Ar8Qw;Z^`AwNtGROFQi98@L#xe>5d_A#d{rA2lc7m^6UR@*ZvDd{kxC5 zw{Rlm-_5H_jeOvsf>*ppjlVlmuwwRJTXp~Z`MGH-2pX*wOe&hYcK!bF;lo-KH!2+h z5hknOty@P4H3}1a7;Nah$$tA<78VwIoqI=v=?^-Yuu(O5Kb;7AI(^wF;^oQk+KK7d zb)(_dUE{t|2kzv4e7>%xV{iMgk={^2ph&~bh)oATGDZ6&3Rv!S+He2Z*LT8RBE-kr z`7#nF3ddN+8DZ2%ITz0)Qa)MgZXW2(`M%WqipSe<^9OoKU<(r9&`O1LLT5o3(AYSf zqzxJ)y>`ik^XId!Hv+&fv!gu3pO@36GtZgBj%yhiaiV_rpA5^+k!v$ODT98<)xo)7 z3!1o4VmExZl!&X+Xhu%#5AS)Tg%v=|g@3ZnPx2(H)B-sG{{sB{&wJ7Ci`4`Ow=)>} z5&Z&(!Sq#wwke^ise=S%oM@KRIql-|Xg(XaaBfR7ni+ksAAF!sRLZ!0ibRkKwaek^ z@2yz5lJW7yE%QK)xcC-!^2tlw?)wSRQ_0x$53L)KCRgnrU73WtQp}W{5+|jrhLYm( z?L_2tJc>(H6RytB-#-e4fGV^6$&$6(!|vX_`_*rx?a5fAYj*PI?Vi2&^vF#Re_PxB zuYRInc+=*k?hj86h>GXVrG>AY_%qm$nNr9rvEBqZO3Yk{8|?%wwU|RoE-9{Cw~l4u z!tHj%3skE8gYU^d%EymCWJ)sWMs-K{%2$gPOohKIzElR!!KNWu>pz^nWJi(OuR@^i zD?r7Se+HuvkdVlD^G!8u_$edYz&b5;oIJ$@2`rI z>jJcZJwWul=v{{GE`GO_NrfIDd^nt4NSps#D}umSf8Ll;S{XjhzY<*sNLc@XfN1!W z4B#iRAZuZTD=8_(!JJ(w=hgovTUkY=hA=45PBdx`LY)ip^S>-+Q#eiw!h38j_7{R! z-zK&g;Jq9Eg%+AG&Vz4v<$Wp@(tCXBL96HF2~ax&`)jZ$EsM_1BjnWJ1o8c*$J!1S z5`4O{j!B4*PYHH+=iE5-1*~DyDO0Jhj{3^E6m7lEEfQ9YtmKLdBBC2EG^vfkN7HV5Xy)1=AIOEW;fO`m9qqkCtD4q9--p zxFEmv%&;ogcKe+R*tlu-_Nfp>KK#Vr)?B?T70-wwK8spRTKNntyWx<|4<9yA1qB7^ zymbjW2Vunu)pal!Hhahs`aikhO*&fE?WO*meQa!OqG@?p!310^!xCNL0L^J69>-NB z2qdxa17riH`wQLC)ev%O1xq(nNYT%%`~%QLIbiX8gCf`lFJCP2+=?jkEAFNTc_=FU$e>y za|IsPO9^S_m3QM%*aNLql$A9P9Jq$^<#+QYsjE>@QCiA?^RNkQPWASdUFe9_m5CM* zKo*pgtgjnGKTUA``uE{S@5(qU6WX6Y(IbRo2Um)p>s#kf1~O6(|lhn>Sp!gRtGD zd^y*66pZM#k51^z4gI;?;V0DV{4C@uB+uC2Kbkc0ZvZ?ILHG38v(n~f{Ra;o5Q}02 ze3VnNMBgqi3f4wX-dJl5+6hU&EZ?|FQW98n7%-+5A{&Q9RHnm!b(;Ee5{@2?bdyaT z&!0cPpN`HZYFiB81g@ljfu`!YkJ%n0sFW=DaSFL^LhsaGE)~ zj}lI>*wh`f`M&aKv=CttRHNNZt|Un>qv!4ik@nRW=#`VVxsa3xkL@ocJ!7)s2G2Nn z2(ggY@rPorCuhB9f&G+FK8$b{k$D6g3Ht3C|8fE&tCpn_v)_HhaV$u&-VnCvYe_7IXrQw!2UuBHdHx7O?e@77wyO zE7R6+dV-Ncbg_zP-m%w7n7^P1o?AEeRc-hQ93qYGJlOBSTaR9}&2A@Nz7=*DDEglbBdW?1MWuP{V&SOR9?Jzfy~g$vcLc6c%wtB zoUT_o;$LpG_7FL|uf2<3e)(mhh7Hpin&rLS*hPjUrNI@%N zsm#tyqU#zD&z%9A1Ne3B$9tEh5(^v7qcw1pQ`+I9(m<0@z|swS`L}FQhxJA?G73R~ z7!53#Qi6;7qYS;yTv%LO%+Ag2dHCoayjoDOG>o`E<)%HwAwRm^E6;HJR(2i{A-Gk- z1PzQ>^a@dbJcFtP{VHVzFL?vX;+GwoQ;)$R!i1Y`b5&uZg<{rZ9o#Z8LjSXlUwpHG z;UKL4=m2h`2HewmvM-ZZ^np(Lpj?!LX6}VKGZPFVO+7xn*hEH>fTHYZn*gFMVe!BX z70)Hr(_yRg=nw8gxAcO=?^@!FA*peBB+FK=|P_J7+$0q zqnBpx6Ci4wOkxRtmHMiU9ESc7(nVzp^_+-p}G{x`n5Gop3#I!o&;ZY%i@4bB(#GR_CsaY<9Y%f&j z&U}Gv42%BH*ps3Eh!({#Ka_y{J9Xb zU$+gx(qh9G>eBzl+v#w5z7hAeUkyU7n{~a+vcLcImI{{qn4dBrZWi4MEDKyQ)}kte zJ*4yHz&_Tvm0F5bUXM+i-tg^P5+o@l7&=ycWj4<#`}$fr{4n;6Rm!+lm+ZIB%DIH0 z<8u>LXbIYzA#e=qSB+XPSVd#CH*M9a7t5Vn`>W1;TJM~d5?AZ2{V~7RXhsuc4&ePc zYE@>PQQGZP`p%x8m-kQSa#+x+i7@bKe7!~V6{}W(vu=rsiBX|r)9h>4_UduZ1?yyE zuJF918q`||#3u#{a0uN4Nz z+>vuIR-)kel0h@lbcht=DFk7G$r#`{JMC)d+Tu*++nO@%M5#@wrswKYj8nkTbECAg zLMzN`0Qc}Q_^2v@B6X~&QiqRTUoH0Rk81S`OH)n$K(`1LkrAJe?2v(eUbd$Z+)4~D zgcA!Wqrqr{iI(EZMUC{%xqT~*PVGV=^5Z4VHSlZ=J-y%_Ot8h >I}LG6&3MI{Y1 zp6}i-H__sDAFb2*I&%e{Rf|*gzjrSQv#Ur@=ib*_ z5tv;(vtKUBPmdg;YIauMBjD0-v2S*&Q-M?VR4OQ09mb6i3}qN<0FuKV@b52}^<3Vz zy8O>&>lVLyXr|I~X1IcM;FSA!MrR3NS=~HXQNVFn;(7CeDFGj(+?68`CA; z&XSf2gN1YSa-6I#bR5n)P$=&?a>tc4V}Yl}Fxy%rWpwohVaP?4eVJ{^n2pkg0Y)|kLx2b3oAIdG_G^1(lo5l2PE)y9B*O79s*J6v z?aZ)`c8XCFDf*2M%{X_s5Ce7-o+vjvHH?wcoB30pROCLtKFX=!`50u&rE-hcL*MLS;o~wz{jJrIc^NCDnQ=!gFTaqJeS8HiwF-1EuWNMY1Xw3qbRB z8+fmPj7(GA%+r;|mTwDxhhgJiXRQTrBl1GW3tWE1ufP6=#_e?XK`+6&OTj*TyH~}# z4R@eRkPT-f5gvdIrh*{B>Y(Ln6LdtW)tGQYgGd4ds-ePAWAq+tBid56$g`w_^5c6P zJIYCfq7S4gXnESrE&J?e^w->8I40_6!nd|-09j>N?|?UpF2jAyZ*`A%hU&nfBqODW z{s8H{sKBs_3{xPCl86w8n5rR7v!Vq&mYB03CNdI0zhf0NTP*{L7P@?+M#jiMn=z(n zbHFG>vuYioJcT=Zm^F4rw&Cs6n^VBSr5qUUu`W7EccD`6jqhs zD?jm^JxATckNshl$S)zHmQXK-#$MAIyxrNIAHrbUr-@Zx%gN_a%mys)l#{mf*r zG@M7-RO;~Xa19VZB?FTY#Ks5Wy-GDLUV)w=Vptg}(=}-L46>MXO&Fu3CyhY7I_vQE z0bv|pKKO<@)};Y3^pFe~kU^x1l0i49Z|6}9bMv0x7jWM|dj=E2PK=~XZI|vr^|`{U z!r}PLV#q5Uj^_CIcpL^&L0m}r#bA}n1tBUK*-J+vGHXjX+`nOnap#edk>UA$7@W(g z)ddO)IbO%8YtQ9PAuj>A>}V>J?jpu>)Um};KrV3t&|nWD)Cr!hki7iN-L0hKj$Taz z18r3Ts00%t#e7G$J9XUvCp9o<@fX>6`kOw^l*rc}=jfa@V$Anud0pUD0KTn!q4$S1j?D0*)5FJFPp8yM zFIp*5+ZpPW4A;fax-HW#l#BzSYnjyqa~sX-4D?g-CVCRcoGPN0upqgKt_V``(E~}q z3@0&b$g|ALZ@*(XV*&lDj8Zp{Hx_~jOThYf!BHn&cZetw^q8Dz*!FR@HTpi1gfxj- zqIVI->Rh%tGuCT%X78*X6G((GMM6zk`3i6M{Y%_Ay$_af$zbMSJJPW(%OZ(syF$Lw z!mwwTeSG8wRMpCeLk@1e(SV8n!Z-Wt0}FaZ|7A|!TTo!zHhO11)1WS1<9`Hf7YzQH zbRQ8$Xhj|Bw-`?{%4@n&LO+99^eAo*X3E~*OqgOsq}mcUg`CRIf1bnv2)y>V#li{7n8!`z_CbmarXWC{-SM95q3so>ipKStd zpAk&f$KgJSRCnsjXt2he6PEDoIu|3vn8n-rs`tFGYOsDQKp|$^XEh(L?G zy`!VFq+}n)WwyL+nG;J*G+#*x>#%Hol$4zJSr2!qha#g_;F;Iz*2zT%*^rz%s9A)C z5Jm|QiK=8}WtAJq3Uq)aGis^ zZqVW}X+`QDoy^mb!6FP00Lk-=PQ9B4AFzvvClGZ}w{o=YA3f>R7Y=Z20yz8My(>&b zZMs890K9ZeRLPyF{w~0(b0aF z2h6kh5?gM-WZE%EWDL}tJGg@U zV;S?6kR0mw?B~JB`PV7@|D~-1o%T<2`~UEbX)ix&UYV?VUM8d)g{q{sCwaHY+5Z8Y Cn&#aA literal 0 HcmV?d00001 diff --git a/results/BUILD b/results/BUILD new file mode 100644 index 0000000..e69de29 diff --git a/results/benchmark/BUILD b/results/benchmark/BUILD new file mode 100644 index 0000000..d53aa8f --- /dev/null +++ b/results/benchmark/BUILD @@ -0,0 +1,5 @@ +filegroup( + name="benchmark_results", + srcs=glob(["*.zip"]), + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/results/benchmark/benchmark_results.zip b/results/benchmark/benchmark_results.zip new file mode 100644 index 0000000..d1216fe --- /dev/null +++ b/results/benchmark/benchmark_results.zip @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c8934a9c77d8b59c40a22a4dcb40a7c2680a36fa3c736639e49631bb174f318b +size 2063700 diff --git a/src/BUILD b/src/BUILD new file mode 100644 index 0000000..e69de29 diff --git a/src/common/BUILD b/src/common/BUILD new file mode 100644 index 0000000..e7c0efb --- /dev/null +++ b/src/common/BUILD @@ -0,0 +1,6 @@ +py_library( + name = "custom_lane_corridor_config", + srcs = ["custom_lane_corridor_config.py"], + data = ["@bark_project//bark/python_wrapper:core.so"], + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/src/common/custom_lane_corridor_config.py b/src/common/custom_lane_corridor_config.py new file mode 100644 index 0000000..af39e82 --- /dev/null +++ b/src/common/custom_lane_corridor_config.py @@ -0,0 +1,81 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import logging + +from bark.core.world.opendrive import XodrDrivingDirection +from bark.core.world.goal_definition import GoalDefinitionPolygon +from bark.runtime.scenario.scenario_generation.config_with_ease import LaneCorridorConfig +from bark.core.geometry import * + + +class CustomLaneCorridorConfig(LaneCorridorConfig): + def __init__(self, + params=None, + **kwargs): + super(CustomLaneCorridorConfig, self).__init__(params, **kwargs) + + def goal(self, world): + # settings are valid for merging map + road_corr = world.map.GetRoadCorridor( + self._road_ids, XodrDrivingDirection.forward) + lane_corr = self._road_corridor.lane_corridors[0] + goal_polygon = Polygon2d([0, 0, 0], [ + Point2d(-10, -10), Point2d(-10, 10), Point2d(10, 10), Point2d(10, -10)]) + goal_point = GetPointAtS( + lane_corr.center_line, lane_corr.center_line.Length()*0.45) + goal_polygon = goal_polygon.Translate(goal_point) + return GoalDefinitionPolygon(goal_polygon) + + +class DeterministicLaneCorridorConfig(CustomLaneCorridorConfig): + def __init__(self, + params=None, + **kwargs): + super(DeterministicLaneCorridorConfig, self).__init__(params, **kwargs) + self._s_start = kwargs.pop("s_start", [30]) + self._vel_start = kwargs.pop("vel_start", [10]) + if not isinstance(self._s_start, list): + raise ValueError("start types must be of type list.") + + def position(self, world): + """ + returns position based on start + """ + if self._road_corridor == None: + world.map.GenerateRoadCorridor( + self._road_ids, XodrDrivingDirection.forward) + self._road_corridor = world.map.GetRoadCorridor( + self._road_ids, XodrDrivingDirection.forward) + if self._road_corridor is None: + return None + if self._lane_corridor is not None: + lane_corr = self._lane_corridor + else: + lane_corr = self._road_corridor.lane_corridors[self._lane_corridor_id] + if lane_corr is None: + return None + centerline = lane_corr.center_line + + if len(self._s_start) == 0: + logging.info( + "no more agents to spawn. If this message is created more than one \ + time, then the scenario has been tried to be created more than \ + once -> ERROR") + return None + + self._current_s = self._s_start.pop(0) + xy_point = GetPointAtS(centerline, self._current_s) + angle = GetTangentAngleAtS(centerline, self._current_s) + + logging.info("Creating agent at x={}, y={}, theta={}".format( + xy_point.x(), xy_point.y(), angle)) + return (xy_point.x(), xy_point.y(), angle) + + def velocity(self): + return self._vel_start diff --git a/src/create_figures/BUILD b/src/create_figures/BUILD new file mode 100644 index 0000000..332726a --- /dev/null +++ b/src/create_figures/BUILD @@ -0,0 +1,17 @@ + +filegroup( + name = "notebooks_folder", + srcs = glob(["*.ipynb"], exclude=["run.py", "run", "__init__.py"]) +) + +# add bark deps here +py_test( + name = "run_notebooks", + srcs = ["run_notebooks.py"], + data = [":notebooks_folder", + "@bark_project//bark/python_wrapper:core.so", + "//results/benchmark:benchmark_results", + ], + deps = ["@bark_project//bark/benchmark:benchmark_runner", + ], +) \ No newline at end of file diff --git a/src/create_figures/plot_benchmark_results.ipynb b/src/create_figures/plot_benchmark_results.ipynb new file mode 100644 index 0000000..040eb08 --- /dev/null +++ b/src/create_figures/plot_benchmark_results.ipynb @@ -0,0 +1,1617 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import copy, os\n", + "from scipy.stats import t\n", + "import pandas as pd\n", + "pd.set_option('display.precision', 2)\n", + "import pickle\n", + "from bark.benchmark.benchmark_runner import BenchmarkResult\n", + "\n", + "import seaborn as sns\n", + "import matplotlib\n", + "\n", + "import itertools\n", + "\n", + "import matplotlib.pyplot as plt\n", + "import matplotlib.gridspec as gridspec" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "data_file_name = 'benchmark_results.zip'\n", + "filepath = \"../../results/benchmark/\"\n", + "\n", + "odir = '/tmp'" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
config_idxscen_setscen_idxbehaviorstepcollisionstepsout_of_mapvelocitygapnum_agentssafe_distancegoal_reachedTerminal
00merging_mid_dense0sa_mcts_20033False34False6.751.071134True[goal_reached]
16merging_light_dense1sa_mcts_20031False32False8.4220.38811True[goal_reached]
212merging_mid_dense2sa_lex_mcts_sd_20042False43False7.047.701113True[goal_reached]
318merging_light_dense3sa_lex_mcts_sd_20038False39False6.8531.07821True[goal_reached]
424merging_mid_dense4Mobil160False161False5.5421.7810161False[steps]
\n", + "
" + ], + "text/plain": [ + " config_idx scen_set scen_idx behavior step \\\n", + "0 0 merging_mid_dense 0 sa_mcts_200 33 \n", + "1 6 merging_light_dense 1 sa_mcts_200 31 \n", + "2 12 merging_mid_dense 2 sa_lex_mcts_sd_200 42 \n", + "3 18 merging_light_dense 3 sa_lex_mcts_sd_200 38 \n", + "4 24 merging_mid_dense 4 Mobil 160 \n", + "\n", + " collision steps out_of_map velocity gap num_agents safe_distance \\\n", + "0 False 34 False 6.75 1.07 11 34 \n", + "1 False 32 False 8.42 20.38 8 11 \n", + "2 False 43 False 7.04 7.70 11 13 \n", + "3 False 39 False 6.85 31.07 8 21 \n", + "4 False 161 False 5.54 21.78 10 161 \n", + "\n", + " goal_reached Terminal \n", + "0 True [goal_reached] \n", + "1 True [goal_reached] \n", + "2 True [goal_reached] \n", + "3 True [goal_reached] \n", + "4 False [steps] " + ] + }, + "execution_count": 3, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "benchmark_result = BenchmarkResult.load(os.path.join(filepath, data_file_name))\n", + "df = benchmark_result.get_data_frame().copy()\n", + "df.head()" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Index(['config_idx', 'scen_set', 'scen_idx', 'behavior', 'step', 'collision',\n", + " 'steps', 'out_of_map', 'velocity', 'gap', 'num_agents', 'safe_distance',\n", + " 'goal_reached', 'Terminal'],\n", + " dtype='object')" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "df.columns" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": { + "scrolled": true + }, + "outputs": [], + "source": [ + "df['success'] = df.Terminal.apply(lambda x: 'goal_reached' in x)\n", + "df['safe_distance_violated'] = df['safe_distance']>0\n", + "for it in ['200']:\n", + " df.replace(to_replace={'sa_lex_mcts_sd_' + it: 'SA-Lex (SD),' + it + ' iterations', \\\n", + " 'sa_mcts_' + it: 'SA,' + it + ' iterations'}, inplace=True)\n", + "df[[\"behavior_model\", \"iterations\"]] = df.behavior.str.split(\",\",expand=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
config_idxscen_setscen_idxbehaviorstepcollisionstepsout_of_mapvelocitygapnum_agentssafe_distancegoal_reachedTerminalsuccesssafe_distance_violatedbehavior_modeliterations
320merging_mid_dense0Mobil160False161False5.5811.6411161False[steps]FalseTrueMobilNone
321merging_mid_dense1Mobil160False161False5.5220.2111151False[steps]FalseTrueMobilNone
322merging_mid_dense2Mobil160False161False5.6318.2311161False[steps]FalseTrueMobilNone
323merging_mid_dense3Mobil160False161False5.6418.5911161False[steps]FalseTrueMobilNone
424merging_mid_dense4Mobil160False161False5.5421.7810161False[steps]FalseTrueMobilNone
425merging_light_dense0Mobil103False104False7.5431.3980True[goal_reached]TrueFalseMobilNone
426merging_light_dense1Mobil97False98False7.5631.9684True[goal_reached]TrueTrueMobilNone
427merging_light_dense2Mobil69False70False7.5939.38854True[goal_reached]TrueTrueMobilNone
428merging_light_dense3Mobil160False161False5.8430.108136False[steps]FalseTrueMobilNone
429merging_light_dense4Mobil160False161False6.1027.808133False[steps]FalseTrueMobilNone
00merging_mid_dense0SA,200 iterations33False34False6.751.071134True[goal_reached]TrueTrueSA200 iterations
01merging_mid_dense1SA,200 iterations35False36False7.806.351128True[goal_reached]TrueTrueSA200 iterations
02merging_mid_dense2SA,200 iterations25False26False11.203.771126True[goal_reached]TrueTrueSA200 iterations
03merging_mid_dense3SA,200 iterations31False32False9.497.391132True[goal_reached]TrueTrueSA200 iterations
04merging_mid_dense4SA,200 iterations34False35False7.609.991023True[goal_reached]TrueTrueSA200 iterations
05merging_light_dense0SA,200 iterations27False28False8.7321.85817True[goal_reached]TrueTrueSA200 iterations
16merging_light_dense1SA,200 iterations31False32False8.4220.38811True[goal_reached]TrueTrueSA200 iterations
17merging_light_dense2SA,200 iterations27False28False7.8231.34811True[goal_reached]TrueTrueSA200 iterations
18merging_light_dense3SA,200 iterations36False37False7.1930.59819True[goal_reached]TrueTrueSA200 iterations
19merging_light_dense4SA,200 iterations25False26False10.6837.23810True[goal_reached]TrueTrueSA200 iterations
110merging_mid_dense0SA-Lex (SD),200 iterations52False53False4.564.611116True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
111merging_mid_dense1SA-Lex (SD),200 iterations42False43False6.207.96119True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
212merging_mid_dense2SA-Lex (SD),200 iterations42False43False7.047.701113True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
213merging_mid_dense3SA-Lex (SD),200 iterations42False43False8.226.871143True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
214merging_mid_dense4SA-Lex (SD),200 iterations40False41False6.5710.861013True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
215merging_light_dense0SA-Lex (SD),200 iterations36False37False7.4118.9180True[goal_reached]TrueFalseSA-Lex (SD)200 iterations
216merging_light_dense1SA-Lex (SD),200 iterations35False36False7.4819.7680True[goal_reached]TrueFalseSA-Lex (SD)200 iterations
217merging_light_dense2SA-Lex (SD),200 iterations34False35False7.6529.46813True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
318merging_light_dense3SA-Lex (SD),200 iterations38False39False6.8531.07821True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
319merging_light_dense4SA-Lex (SD),200 iterations26False27False10.4136.57810True[goal_reached]TrueTrueSA-Lex (SD)200 iterations
\n", + "
" + ], + "text/plain": [ + " config_idx scen_set scen_idx behavior \\\n", + "3 20 merging_mid_dense 0 Mobil \n", + "3 21 merging_mid_dense 1 Mobil \n", + "3 22 merging_mid_dense 2 Mobil \n", + "3 23 merging_mid_dense 3 Mobil \n", + "4 24 merging_mid_dense 4 Mobil \n", + "4 25 merging_light_dense 0 Mobil \n", + "4 26 merging_light_dense 1 Mobil \n", + "4 27 merging_light_dense 2 Mobil \n", + "4 28 merging_light_dense 3 Mobil \n", + "4 29 merging_light_dense 4 Mobil \n", + "0 0 merging_mid_dense 0 SA,200 iterations \n", + "0 1 merging_mid_dense 1 SA,200 iterations \n", + "0 2 merging_mid_dense 2 SA,200 iterations \n", + "0 3 merging_mid_dense 3 SA,200 iterations \n", + "0 4 merging_mid_dense 4 SA,200 iterations \n", + "0 5 merging_light_dense 0 SA,200 iterations \n", + "1 6 merging_light_dense 1 SA,200 iterations \n", + "1 7 merging_light_dense 2 SA,200 iterations \n", + "1 8 merging_light_dense 3 SA,200 iterations \n", + "1 9 merging_light_dense 4 SA,200 iterations \n", + "1 10 merging_mid_dense 0 SA-Lex (SD),200 iterations \n", + "1 11 merging_mid_dense 1 SA-Lex (SD),200 iterations \n", + "2 12 merging_mid_dense 2 SA-Lex (SD),200 iterations \n", + "2 13 merging_mid_dense 3 SA-Lex (SD),200 iterations \n", + "2 14 merging_mid_dense 4 SA-Lex (SD),200 iterations \n", + "2 15 merging_light_dense 0 SA-Lex (SD),200 iterations \n", + "2 16 merging_light_dense 1 SA-Lex (SD),200 iterations \n", + "2 17 merging_light_dense 2 SA-Lex (SD),200 iterations \n", + "3 18 merging_light_dense 3 SA-Lex (SD),200 iterations \n", + "3 19 merging_light_dense 4 SA-Lex (SD),200 iterations \n", + "\n", + " step collision steps out_of_map velocity gap num_agents \\\n", + "3 160 False 161 False 5.58 11.64 11 \n", + "3 160 False 161 False 5.52 20.21 11 \n", + "3 160 False 161 False 5.63 18.23 11 \n", + "3 160 False 161 False 5.64 18.59 11 \n", + "4 160 False 161 False 5.54 21.78 10 \n", + "4 103 False 104 False 7.54 31.39 8 \n", + "4 97 False 98 False 7.56 31.96 8 \n", + "4 69 False 70 False 7.59 39.38 8 \n", + "4 160 False 161 False 5.84 30.10 8 \n", + "4 160 False 161 False 6.10 27.80 8 \n", + "0 33 False 34 False 6.75 1.07 11 \n", + "0 35 False 36 False 7.80 6.35 11 \n", + "0 25 False 26 False 11.20 3.77 11 \n", + "0 31 False 32 False 9.49 7.39 11 \n", + "0 34 False 35 False 7.60 9.99 10 \n", + "0 27 False 28 False 8.73 21.85 8 \n", + "1 31 False 32 False 8.42 20.38 8 \n", + "1 27 False 28 False 7.82 31.34 8 \n", + "1 36 False 37 False 7.19 30.59 8 \n", + "1 25 False 26 False 10.68 37.23 8 \n", + "1 52 False 53 False 4.56 4.61 11 \n", + "1 42 False 43 False 6.20 7.96 11 \n", + "2 42 False 43 False 7.04 7.70 11 \n", + "2 42 False 43 False 8.22 6.87 11 \n", + "2 40 False 41 False 6.57 10.86 10 \n", + "2 36 False 37 False 7.41 18.91 8 \n", + "2 35 False 36 False 7.48 19.76 8 \n", + "2 34 False 35 False 7.65 29.46 8 \n", + "3 38 False 39 False 6.85 31.07 8 \n", + "3 26 False 27 False 10.41 36.57 8 \n", + "\n", + " safe_distance goal_reached Terminal success \\\n", + "3 161 False [steps] False \n", + "3 151 False [steps] False \n", + "3 161 False [steps] False \n", + "3 161 False [steps] False \n", + "4 161 False [steps] False \n", + "4 0 True [goal_reached] True \n", + "4 4 True [goal_reached] True \n", + "4 54 True [goal_reached] True \n", + "4 136 False [steps] False \n", + "4 133 False [steps] False \n", + "0 34 True [goal_reached] True \n", + "0 28 True [goal_reached] True \n", + "0 26 True [goal_reached] True \n", + "0 32 True [goal_reached] True \n", + "0 23 True [goal_reached] True \n", + "0 17 True [goal_reached] True \n", + "1 11 True [goal_reached] True \n", + "1 11 True [goal_reached] True \n", + "1 19 True [goal_reached] True \n", + "1 10 True [goal_reached] True \n", + "1 16 True [goal_reached] True \n", + "1 9 True [goal_reached] True \n", + "2 13 True [goal_reached] True \n", + "2 43 True [goal_reached] True \n", + "2 13 True [goal_reached] True \n", + "2 0 True [goal_reached] True \n", + "2 0 True [goal_reached] True \n", + "2 13 True [goal_reached] True \n", + "3 21 True [goal_reached] True \n", + "3 10 True [goal_reached] True \n", + "\n", + " safe_distance_violated behavior_model iterations \n", + "3 True Mobil None \n", + "3 True Mobil None \n", + "3 True Mobil None \n", + "3 True Mobil None \n", + "4 True Mobil None \n", + "4 False Mobil None \n", + "4 True Mobil None \n", + "4 True Mobil None \n", + "4 True Mobil None \n", + "4 True Mobil None \n", + "0 True SA 200 iterations \n", + "0 True SA 200 iterations \n", + "0 True SA 200 iterations \n", + "0 True SA 200 iterations \n", + "0 True SA 200 iterations \n", + "0 True SA 200 iterations \n", + "1 True SA 200 iterations \n", + "1 True SA 200 iterations \n", + "1 True SA 200 iterations \n", + "1 True SA 200 iterations \n", + "1 True SA-Lex (SD) 200 iterations \n", + "1 True SA-Lex (SD) 200 iterations \n", + "2 True SA-Lex (SD) 200 iterations \n", + "2 True SA-Lex (SD) 200 iterations \n", + "2 True SA-Lex (SD) 200 iterations \n", + "2 False SA-Lex (SD) 200 iterations \n", + "2 False SA-Lex (SD) 200 iterations \n", + "2 True SA-Lex (SD) 200 iterations \n", + "3 True SA-Lex (SD) 200 iterations \n", + "3 True SA-Lex (SD) 200 iterations " + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "df.sort_values(by=['behavior', 'config_idx'])" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
config_idxscen_setscen_idxstepcollisionstepsout_of_mapvelocitygapnum_agentssafe_distancegoal_reachedTerminalsuccesssafe_distance_violatedbehavior_modeliterations
behavior
Mobil101010101010101010101010101010100
SA,200 iterations1010101010101010101010101010101010
SA-Lex (SD),200 iterations1010101010101010101010101010101010
\n", + "
" + ], + "text/plain": [ + " config_idx scen_set scen_idx step collision \\\n", + "behavior \n", + "Mobil 10 10 10 10 10 \n", + "SA,200 iterations 10 10 10 10 10 \n", + "SA-Lex (SD),200 iterations 10 10 10 10 10 \n", + "\n", + " steps out_of_map velocity gap num_agents \\\n", + "behavior \n", + "Mobil 10 10 10 10 10 \n", + "SA,200 iterations 10 10 10 10 10 \n", + "SA-Lex (SD),200 iterations 10 10 10 10 10 \n", + "\n", + " safe_distance goal_reached Terminal success \\\n", + "behavior \n", + "Mobil 10 10 10 10 \n", + "SA,200 iterations 10 10 10 10 \n", + "SA-Lex (SD),200 iterations 10 10 10 10 \n", + "\n", + " safe_distance_violated behavior_model iterations \n", + "behavior \n", + "Mobil 10 10 0 \n", + "SA,200 iterations 10 10 10 \n", + "SA-Lex (SD),200 iterations 10 10 10 " + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "df.groupby('behavior').count()" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "def mean_from_bool(col, df):\n", + " tmp_df = copy.deepcopy(df)\n", + " tmp_df[col] = df[col] * 1.0\n", + " stats = df.groupby('behavior')[col].agg(['sum','mean', 'count', 'std'])\n", + " return stats" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Collisions" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
summeancountstd
behavior
Mobil0False100.0
SA,200 iterations0False100.0
SA-Lex (SD),200 iterations0False100.0
\n", + "
" + ], + "text/plain": [ + " sum mean count std\n", + "behavior \n", + "Mobil 0 False 10 0.0\n", + "SA,200 iterations 0 False 10 0.0\n", + "SA-Lex (SD),200 iterations 0 False 10 0.0" + ] + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "mean_from_bool('collision', df)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Safe Distance rule" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
summeancountstd
behavior
Mobil7True70.0
\n", + "
" + ], + "text/plain": [ + " sum mean count std\n", + "behavior \n", + "Mobil 7 True 7 0.0" + ] + }, + "execution_count": 10, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "mean_from_bool('safe_distance_violated', df[df.success == False])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Success" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
summeancountstd
behavior
Mobil30.3100.48
SA,200 iterations101.0100.00
SA-Lex (SD),200 iterations101.0100.00
\n", + "
" + ], + "text/plain": [ + " sum mean count std\n", + "behavior \n", + "Mobil 3 0.3 10 0.48\n", + "SA,200 iterations 10 1.0 10 0.00\n", + "SA-Lex (SD),200 iterations 10 1.0 10 0.00" + ] + }, + "execution_count": 11, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "mean_from_bool('success', df)" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "def format_upper_axis(axis):\n", + " axis.xaxis.set_ticklabels([])\n", + " axis.set_xlabel(\"\")\n", + "\n", + "def set_style():\n", + " plt.style.use(['seaborn-white', 'seaborn-paper'])\n", + " matplotlib.rc(\"font\", family=\"DejaVu Sans\")" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [], + "source": [ + "# drawing params:\n", + "err_width_bars = .0\n", + "palette_name = \"Set2\"\n", + "\n", + "estimator=lambda x: sum(x==1)*100.0/len(x) # scale to percent\n", + "order = ['SA', 'SA-Lex (SD)', 'Mobil']" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# figure definition\n", + "fig = plt.figure()\n", + "set_style()\n", + "gs = gridspec.GridSpec(3, 1, width_ratios=[1], height_ratios=[1, 1, 1], wspace = 0.02, hspace = 0.1)\n", + "axis00 = plt.subplot(gs[0])\n", + "axis10 = plt.subplot(gs[1])\n", + "axis20 = plt.subplot(gs[2])\n", + "\n", + "# barplot - collision\n", + "sns.barplot(x=\"behavior_model\", y=\"collision\", order=order, estimator=estimator, \n", + " data=df, errwidth=err_width_bars, palette=palette_name, ax=axis00)\n", + "sns.barplot(x=\"behavior_model\", y=\"success\", order=order, estimator=estimator, \n", + " data=df, errwidth=err_width_bars, palette=palette_name, ax=axis10)\n", + "sns.barplot(x=\"behavior_model\", y=\"safe_distance_violated\", order=order, estimator=estimator, \n", + " data=df, errwidth=err_width_bars, palette=palette_name, ax=axis20)\n", + "\n", + "axis20.set_xlabel(\"Variants\")\n", + "\n", + "axis00.set_ylabel(\"% Collision\")\n", + "axis10.set_ylabel(\"% Success\")\n", + "axis20.set_ylabel(\"% SD\\nViolation\")\n", + "\n", + "# format\n", + "format_upper_axis(axis00)\n", + "format_upper_axis(axis10)\n", + "\n", + "axis00.tick_params(axis='both', which='major', pad=2.5)\n", + "axis10.tick_params(axis='both', which='major', pad=2.5)\n", + "axis20.tick_params(axis='both', which='major', pad=2.5)\n", + "\n", + "axis00.tick_params(axis=u'both', which=u'both',length=0)\n", + "axis10.tick_params(axis=u'both', which=u'both',length=0)\n", + "axis20.tick_params(axis=u'both', which=u'both',length=0)\n", + "\n", + "fig.set_size_inches(6, 4)\n", + "plt.savefig(\"/tmp/benchmark_results.png\")\n", + "plt.show(block=True)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "celltoolbar": "Edit Metadata", + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.7.7" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/src/create_figures/run_notebooks.py b/src/create_figures/run_notebooks.py new file mode 100644 index 0000000..f338d5b --- /dev/null +++ b/src/create_figures/run_notebooks.py @@ -0,0 +1,7 @@ +import os +from notebook import notebookapp +from pathlib import Path + +os.chdir("./src/create_figures") + +notebookapp.main() diff --git a/src/database/BUILD b/src/database/BUILD new file mode 100644 index 0000000..51878c1 --- /dev/null +++ b/src/database/BUILD @@ -0,0 +1,10 @@ +filegroup( + name="database", + srcs=glob([ + "scenario_sets/**/*.json", + "scenario_sets/serialized/**", + "maps/*.xodr", + ]), + visibility = ["//visibility:public"], +) + diff --git a/src/database/maps/merging_long_v01.xodr b/src/database/maps/merging_long_v01.xodr new file mode 100644 index 0000000..5925aa3 --- /dev/null +++ b/src/database/maps/merging_long_v01.xodr @@ -0,0 +1,178 @@ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+
\ No newline at end of file diff --git a/src/database/scenario_sets/merging_light_dense.json b/src/database/scenario_sets/merging_light_dense.json new file mode 100644 index 0000000..07b2186 --- /dev/null +++ b/src/database/scenario_sets/merging_light_dense.json @@ -0,0 +1,211 @@ +{ + "Scenario": { + "Generation": { + "GeneratorName": "ConfigurableScenarioGeneration", + "GeneratorSeed": 2000, + "SetName": "merging_light_dense", + "SetDescription": "", + "NumScenarios": 20, + "NumSets": 1, + "ConfigurableScenarioGeneration": { + "SinksSources": [ + { + "SourceSink": [ + [ + 104.92, + 103.59 + ], + [ + -16.064, + 108.07 + ] + ], + "Description": "left_lane", + "ConfigAgentStatesGeometries": { + "Type": "UniformVehicleDistribution", + "LanePositions": [ + 0 + ], + "VehicleDistanceRange": [ + 20, + 30 + ], + "OtherVehicleVelocityRange": [ + 5.3, + 6.1 + ], + "SRange": [ + 0.0, + 0.8 + ] + }, + "ConfigBehaviorModels": { + "Type": "FixedBehaviorType", + "ModelType": "BehaviorIDMClassic", + "ModelParams": { + "BehaviorIDMClassic": { + "MaxVelocity": 60.0, + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -5.0, + "AccelerationUpperBound": 8.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 1.6699999570846558, + "MinVelocity": 0.0, + "Exponent": 4, + "BrakeForLaneEnd": false, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 20.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + "ConfigExecutionModels": { + "Type": "FixedExecutionType", + "ModelType": "ExecutionModelInterpolate" + }, + "ConfigDynamicModels": { + "Type": "FixedDynamicType", + "ModelType": "SingleTrackModel" + }, + "ConfigGoalDefinitions": { + "Type": "FixedGoalTypes", + "GoalTypeControlled": "LaneChangeLeft", + "EnforceControlledGoal": false, + "EnforceOthersGoal": false, + "GoalTypeOthers": "LaneChangeLeft", + "MaxLateralDist": [ + 0.8, + 0.8 + ], + "LongitudinalRange": [ + 0.0, + 1.0 + ], + "MaxOrientationDifference": [ + 0.1, + 0.1 + ], + "VelocityRange": [ + 5.0, + 15.0 + ] + }, + "ConfigControlledAgents": { + "Type": "NoneControlled" + }, + "AgentParams": { + "MaxHistoryLength": 50 + } + }, + { + "SourceSink": [ + [ + 104.92, + 103.59 + ], + [ + -16.064, + 108.07 + ] + ], + "Description": "right_lane", + "ConfigAgentStatesGeometries": { + "Type": "UniformVehicleDistribution", + "LanePositions": [ + 1 + ], + "VehicleDistanceRange": [ + 20, + 30 + ], + "OtherVehicleVelocityRange": [ + 5.5, + 11.1 + ], + "SRange": [ + 0.5, + 0.51 + ] + }, + "ConfigBehaviorModels": { + "Type": "FixedBehaviorType", + "ModelType": "BehaviorIDMClassic", + "ModelParams": { + "BehaviorIDMClassic": { + "MaxVelocity": 60.0, + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -5.0, + "AccelerationUpperBound": 8.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 1.6699999570846558, + "MinVelocity": 0.0, + "Exponent": 4, + "BrakeForLaneEnd": false, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 20.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + "ConfigExecutionModels": { + "Type": "FixedExecutionType", + "ModelType": "ExecutionModelInterpolate" + }, + "ConfigDynamicModels": { + "Type": "FixedDynamicType", + "ModelType": "SingleTrackModel" + }, + "ConfigGoalDefinitions": { + "Type": "FixedGoalTypes", + "GoalTypeControlled": "LaneChangeLeft", + "EnforceControlledGoal": true, + "EnforceOthersGoal": false, + "GoalTypeOthers": "LaneChangeLeft", + "MaxLateralDist": [ + 0.8, + 0.8 + ], + "LongitudinalRange": [ + 0.0, + 0.8 + ], + "MaxOrientationDifference": [ + 0.1, + 0.1 + ], + "VelocityRange": [ + 5.0, + 15.0 + ] + }, + "ConfigControlledAgents": { + "Type": "RandomSingleAgent" + }, + "AgentParams": { + "MaxHistoryLength": 50 + } + } + ], + "MapFilename": "maps/merging_long_v01.xodr", + "ConflictResolution": { + "left_lane/right_lane": [ + 0.2, + 0.8 + ] + } + } + } + }, + "World": { + "remove_agents_out_of_map": false + }, + "Simulation": { + "StepTime": 0.05 + } +} \ No newline at end of file diff --git a/src/database/scenario_sets/merging_mid_dense.json b/src/database/scenario_sets/merging_mid_dense.json new file mode 100644 index 0000000..1072e21 --- /dev/null +++ b/src/database/scenario_sets/merging_mid_dense.json @@ -0,0 +1,211 @@ +{ + "Scenario": { + "Generation": { + "GeneratorName": "ConfigurableScenarioGeneration", + "GeneratorSeed": 2000, + "SetName": "merging_mid_dense", + "SetDescription": "", + "NumScenarios": 20, + "NumSets": 1, + "ConfigurableScenarioGeneration": { + "SinksSources": [ + { + "SourceSink": [ + [ + 104.92, + 103.59 + ], + [ + -16.064, + 108.07 + ] + ], + "Description": "left_lane", + "ConfigAgentStatesGeometries": { + "Type": "UniformVehicleDistribution", + "LanePositions": [ + 0 + ], + "VehicleDistanceRange": [ + 10, + 20 + ], + "OtherVehicleVelocityRange": [ + 5.3, + 6.1 + ], + "SRange": [ + 0.0, + 0.8 + ] + }, + "ConfigBehaviorModels": { + "Type": "FixedBehaviorType", + "ModelType": "BehaviorIDMClassic", + "ModelParams": { + "BehaviorIDMClassic": { + "MaxVelocity": 60.0, + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -5.0, + "AccelerationUpperBound": 8.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 1.6699999570846558, + "MinVelocity": 0.0, + "Exponent": 4, + "BrakeForLaneEnd": false, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 20.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + "ConfigExecutionModels": { + "Type": "FixedExecutionType", + "ModelType": "ExecutionModelInterpolate" + }, + "ConfigDynamicModels": { + "Type": "FixedDynamicType", + "ModelType": "SingleTrackModel" + }, + "ConfigGoalDefinitions": { + "Type": "FixedGoalTypes", + "GoalTypeControlled": "LaneChangeLeft", + "EnforceControlledGoal": false, + "EnforceOthersGoal": false, + "GoalTypeOthers": "LaneChangeLeft", + "MaxLateralDist": [ + 0.8, + 0.8 + ], + "LongitudinalRange": [ + 0.0, + 1.0 + ], + "MaxOrientationDifference": [ + 0.1, + 0.1 + ], + "VelocityRange": [ + 5.0, + 15.0 + ] + }, + "ConfigControlledAgents": { + "Type": "NoneControlled" + }, + "AgentParams": { + "MaxHistoryLength": 50 + } + }, + { + "SourceSink": [ + [ + 104.92, + 103.59 + ], + [ + -16.064, + 108.07 + ] + ], + "Description": "right_lane", + "ConfigAgentStatesGeometries": { + "Type": "UniformVehicleDistribution", + "LanePositions": [ + 1 + ], + "VehicleDistanceRange": [ + 10, + 20 + ], + "OtherVehicleVelocityRange": [ + 5.5, + 11.1 + ], + "SRange": [ + 0.5, + 0.51 + ] + }, + "ConfigBehaviorModels": { + "Type": "FixedBehaviorType", + "ModelType": "BehaviorIDMClassic", + "ModelParams": { + "BehaviorIDMClassic": { + "MaxVelocity": 60.0, + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -5.0, + "AccelerationUpperBound": 8.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 1.6699999570846558, + "MinVelocity": 0.0, + "Exponent": 4, + "BrakeForLaneEnd": false, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 20.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + "ConfigExecutionModels": { + "Type": "FixedExecutionType", + "ModelType": "ExecutionModelInterpolate" + }, + "ConfigDynamicModels": { + "Type": "FixedDynamicType", + "ModelType": "SingleTrackModel" + }, + "ConfigGoalDefinitions": { + "Type": "FixedGoalTypes", + "GoalTypeControlled": "LaneChangeLeft", + "EnforceControlledGoal": true, + "EnforceOthersGoal": false, + "GoalTypeOthers": "LaneChangeLeft", + "MaxLateralDist": [ + 0.8, + 0.8 + ], + "LongitudinalRange": [ + 0.0, + 0.8 + ], + "MaxOrientationDifference": [ + 0.1, + 0.1 + ], + "VelocityRange": [ + 5.0, + 15.0 + ] + }, + "ConfigControlledAgents": { + "Type": "RandomSingleAgent" + }, + "AgentParams": { + "MaxHistoryLength": 50 + } + } + ], + "MapFilename": "maps/merging_long_v01.xodr", + "ConflictResolution": { + "left_lane/right_lane": [ + 0.2, + 0.8 + ] + } + } + } + }, + "World": { + "remove_agents_out_of_map": false + }, + "Simulation": { + "StepTime": 0.05 + } +} \ No newline at end of file diff --git a/src/mcts_config/BUILD b/src/mcts_config/BUILD new file mode 100644 index 0000000..e93067d --- /dev/null +++ b/src/mcts_config/BUILD @@ -0,0 +1,48 @@ +py_library( + name = "mcts_config", + srcs = ["mcts_config.py"], + data = [ + "@bark_project//bark/python_wrapper:core.so", + ], + imports = ["../python/"], + visibility = ["//visibility:public"], + deps = [ + ":mcts_behavior_config_reader", + "@bark_project//bark/runtime", + "@bark_project//bark/runtime/scenario/scenario_generation", + ], +) + +py_library( + name = "mcts_behavior_config_reader", + srcs = [ + "mcts_behavior_config_reader.py", + ], + data = [ + "@bark_project//bark/python_wrapper:core.so", + ], + imports = ["../python/"], + visibility = ["//visibility:public"], + deps = [ + "@bark_project//bark/runtime", + "@bark_project//bark/runtime/scenario/scenario_generation", + "//src/traffic_rules:traffic_rules" + ], +) + +py_test( + name = "mcts_config_test", + srcs = ["mcts_config_test.py"], + data = [ + "//src/database:database", + "//src/mcts_config/params:mcts_params", + "@bark_project//bark/python_wrapper:core.so", + ], + imports = ["../python/"], + deps = [ + ":mcts_config", + "@bark_project//bark/runtime", + "@bark_project//bark/runtime/scenario/scenario_generation", + "@bark_project//bark/runtime/scenario/scenario_generation/config_readers", + ], +) diff --git a/src/mcts_config/mcts_behavior_config_reader.py b/src/mcts_config/mcts_behavior_config_reader.py new file mode 100644 index 0000000..1e9849a --- /dev/null +++ b/src/mcts_config/mcts_behavior_config_reader.py @@ -0,0 +1,92 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +from bark.core.models.behavior import * +from src.traffic_rules.rule_generation import make_rule_monitors, make_labels +from bark.core.world.prediction import PredictionSettings +from bark.core.models.dynamic import SingleTrackModel +from bark.runtime.commons.parameters import ParameterServer +from bark.runtime.commons import ModelJsonConversion + +prim_param_server = [] + + +def mcts_behavior_from_config(param_server, ego_id=None, iterations=None): + if iterations: + param_server["BehaviorRulesMcts"]["MaxNumIterations"] = iterations + + # LABELS + label_params = param_server["BehaviorRulesMcts"]["Labels", + "Definition of labels, required for the rules", []] + # The collision label is always required for terminal state assessment! + label_params.append( + {"type": "CollisionEgoLabelFunction", "label_str": "collision_ego"}) + labels = make_labels(label_params) + + # RULES + rules = make_rule_monitors( + param_server["BehaviorRulesMcts"]["Rules"]["common", "Rules valid for all agents incl. ego", []]) + + # DYNAMIC MODEL + dynamic_model = SingleTrackModel(param_server) + + # PREDICTION SETTING + prediction_settings = prediction_settings_from_config( + param_server["BehaviorRulesMcts"], dynamic_model) + + behavior = BehaviorRulesMctsUct( + param_server, prediction_settings, labels, rules, {}) + return behavior + + +def prediction_settings_from_config(param_server, dynamic_model): + model_converter = ModelJsonConversion() + # EGO BEHAVIOR MODEL + ego_model = mp_macro_actions_from_config( + param_server["PredictionSettings"]["EgoModelParams"]) + + # OTHER AGENTS MODEL + default_behavior_name = param_server["PredictionSettings"]["DefaultModelName", + "", "BehaviorMobilRuleBased"] + default_behavior_params = param_server["PredictionSettings"]["DefaultModelParams"] + if isinstance(default_behavior_params, dict): + default_behavior_params = ParameterServer( + log_if_default=True, json=default_behavior_params) + param_server["PredictionSettings"]["DefaultModel"] = default_behavior_params + if default_behavior_name == "None": + default_model = None + else: + try: + default_model = model_converter.convert_model( + default_behavior_name, default_behavior_params) + except: + raise ValueError("Could not retrieve default_model") + prediction_settings = PredictionSettings( + ego_model, default_model, None, []) + return prediction_settings + + +def mp_macro_actions_from_config(param_server): + primitives = primitives_from_config( + param_server["BehaviorMPMacroActions"]["Primitives"]) + model = BehaviorMPMacroActions(param_server, primitives) + return model + + +def primitives_from_config(primitives): + prim = [] + for param_prim_object in primitives: + prim_dict = param_prim_object.ConvertToDict() + prim_params = list(prim_dict.items())[0] + prim_type = prim_params[0] + param_server = ParameterServer( + json=prim_params[1], log_if_default=True) + prim_param_server.append(param_server) + prim_dict[prim_type] = param_server + prim.append(eval("{}(param_server)".format(prim_type))) + return prim diff --git a/src/mcts_config/mcts_config.py b/src/mcts_config/mcts_config.py new file mode 100644 index 0000000..897d711 --- /dev/null +++ b/src/mcts_config/mcts_config.py @@ -0,0 +1,48 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import os + +from bark.runtime.commons.parameters import ParameterServer +from src.mcts_config.mcts_behavior_config_reader import \ + mcts_behavior_from_config + + +def dump_mcts_default_params(dir): + params = ParameterServer() + sa_mcts_behavior = mcts_behavior_from_config(params) + + params.Save(filename=os.path.join(dir, "sa_mcts.json")) + params.Save(filename=os.path.join(dir, "sa_mcts_default_description.json"), + print_description=True) + + +def create_mcts_configurations(param_directory, iterations, variants=None): + common_params_fname = 'common.json' + params_dict = {} + configuration_dict = {} + for root, dirs, files in os.walk(param_directory): + for file in files: + base = os.path.basename(file) + (configuration_name, ext) = os.path.splitext(base) + if ext == '.json' and base != common_params_fname: + print(configuration_name) + if ((variants is None) or (configuration_name in variants)): + for it in iterations: + full_config_name = "{}_{}".format( + configuration_name, it) + params = ParameterServer(filename=os.path.join( + root, file), log_if_default=True) + action_set_params = ParameterServer(filename=os.path.join(param_directory, common_params_fname), + log_if_default=True) + params.AppendParamServer(action_set_params) + behavior = mcts_behavior_from_config( + params, iterations=(it)) + configuration_dict[full_config_name] = behavior + params_dict[full_config_name] = params + return configuration_dict, params_dict diff --git a/src/mcts_config/mcts_config_test.py b/src/mcts_config/mcts_config_test.py new file mode 100644 index 0000000..c23a90c --- /dev/null +++ b/src/mcts_config/mcts_config_test.py @@ -0,0 +1,46 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import unittest +import pickle + +from src.mcts_config.mcts_config import dump_mcts_default_params, \ + create_mcts_configurations +from src.traffic_rules.rule_generation import make_rule_monitors + + +def pickle_unpickle(object): + d = pickle.dumps(object) + return pickle.loads(d) + + +class MctsConfigTests(unittest.TestCase): + def test_dump_defaults(self): + dump_mcts_default_params("/tmp/") + + def test_create_config_dict(self): + config_dict, params = create_mcts_configurations( + "src/mcts_config/params/", [200]) + for config_name, behavior in config_dict.items(): + print(config_name, behavior) + unpickled = pickle_unpickle(behavior) + print(unpickled) + print("##############") + + def test_rules(self): + it = 200 + config_dict, params = create_mcts_configurations( + "src/mcts_config/params/", [it]) + variant_name = list(config_dict.keys())[0] + print(params[variant_name]["BehaviorRulesMcts"]["Rules"]["common"]) + rules = make_rule_monitors(params[variant_name] + ["BehaviorRulesMcts"]["Rules"]["common"]) + + +if __name__ == '__main__': + unittest.main() diff --git a/src/mcts_config/params/BUILD b/src/mcts_config/params/BUILD new file mode 100644 index 0000000..3271748 --- /dev/null +++ b/src/mcts_config/params/BUILD @@ -0,0 +1,5 @@ +filegroup( + name="mcts_params", + srcs=glob(["**/*.json"]), + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/src/mcts_config/params/common.json b/src/mcts_config/params/common.json new file mode 100644 index 0000000..e18e7d2 --- /dev/null +++ b/src/mcts_config/params/common.json @@ -0,0 +1,254 @@ +{ + "BehaviorRulesMcts": { + "MaxSearchTime": 2147483647, + "DumpTree": false, + "RandomSeed": 1000, + "DiscountFactor": 0.9, + "MaxNumIterationsRandomHeuristic": 20, + "EnableProgressiveWidening": false, + "ProgressiveWideningAlpha": 0.5, + "EpsilonGreedy": 0.1, + "Decay1": 0.8, + "Decay2": 0.12, + "StateParameters": { + "PredictionTimeSpan": 0.5, + "DesiredVelocity": 14.0, + "Horizon": 20, + "GoalReward": 0.0 + }, + "PredictionSettings": { + "EgoModelName": "BehaviorMPMacroActions", + "EgoModelParams": { + "BehaviorMPMacroActions": { + "CheckValidityInPlan": false, + "Primitives": [ + { + "PrimitiveConstAccStayLane": { + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": 0.0 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + { + "PrimitiveConstAccStayLane": { + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": 2.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + { + "PrimitiveConstAccStayLane": { + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": -2.0 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + { + "PrimitiveConstAccStayLane": { + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": -8.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + { + "PrimitiveGapKeeping": { + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": 0.0 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + } + } + }, + { + "PrimitiveConstAccChangeToLeft": { + "MinLength": 30.0, + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + }, + { + "PrimitiveConstAccChangeToRight": { + "MinLength": 100.0, + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + }, + "PrimitiveConstAccStayLane": { + "Acceleration": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 2.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 14.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 30.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + } + } + } + ] + }, + "BehaviorMotionPrimitives": { + "IntegrationTimeDelta": 0.05 + } + }, + "SpecificPredictionModelName": "None" + } + }, + "DynamicModel": { + "wheel_base": 2.700000047683716, + "delta_max": 0.20000000298023224, + "LatAccLeftMax": 4.0, + "LatAccRightMax": 4.0, + "LonAccelerationMax": 4.0, + "LonAccelerationMin": -8.0 + } +} \ No newline at end of file diff --git a/src/mcts_config/params/mobil.json b/src/mcts_config/params/mobil.json new file mode 100644 index 0000000..dd5efaa --- /dev/null +++ b/src/mcts_config/params/mobil.json @@ -0,0 +1,39 @@ +{ + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 25.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + }, + "BehaviorLaneChangeRuleBased": { + "MinRemainingLaneCorridorDistance": 80.0, + "MinVehicleRearDistance": 0.5, + "MinVehicleFrontDistance": 1.0, + "TimeKeepingGap": 0.5 + }, + "BehaviorMobilRuleBased": { + "AThr": 0.2, + "Politeness": 0.0, + "SafeDeceleration": 12.0 + }, + "DynamicModel": { + "LatAccLeftMax": 4.0, + "LatAccRightMax": 4.0, + "LonAccelerationMax": 4.0, + "LonAccelerationMin": -8.0 + } +} \ No newline at end of file diff --git a/src/mcts_config/params/sa_lex_mcts_sd.json b/src/mcts_config/params/sa_lex_mcts_sd.json new file mode 100644 index 0000000..e65b29d --- /dev/null +++ b/src/mcts_config/params/sa_lex_mcts_sd.json @@ -0,0 +1,104 @@ +{ + "BehaviorRulesMcts": { + "MultiAgent": false, + "MaxNumIterations": 5000, + "RewardVectorSize": 3, + "CooperationFactor": 0.0, + "ReturnLowerBound": [ + -1.0, + -1.0, + -1000.0 + ], + "ReturnUpperBound": [ + 0.0, + 0.0, + 0.0 + ], + "Threshold": [ + -0.19, + -0.3, + 1000000.0 + ], + "UCTExplorationConstant": [ + 1.41, + 1.41, + 1.41 + ], + "Rules": { + "common": [ + { + "formula": "G !collision_ego", + "weight": 0.0, + "priority": 0 + }, + { + "formula": "G sd_front", + "weight": -1.0, + "priority": 1 + } + ] + }, + "Labels": [ + { + "type": "SafeDistanceLabelFunction", + "label_str": "sd_front", + "to_rear": false, + "delta_ego": 1.0, + "delta_others": 1.0, + "a_e": -7.84, + "a_o": -7.84, + "consider_crossing_corridors": true, + "max_agents_for_crossing": 4, + "use_frac_param_from_world": false, + "lateral_difference_threshold": 2.0, + "check_lateral_dist": false + } + ], + "StateParameters": { + "CollisionWeight": -1.0, + "OutOfMapWeight": -1.0, + "PotentialWeight": 32.0, + "AccelerationWeight": -0.5, + "RadialAccelerationWeight": 0.0, + "DesiredVelocityWeight": -5.0, + "LaneCenterDeviationWeight": 0.0, + "UseRuleRewardForEgoOnly": false + }, + "PredictionSettings": { + "DefaultModelName": "BehaviorMobilRuleBased", + "DefaultModelParams": { + "BehaviorMobilRuleBased": { + "AThr": 0.2, + "Politeness": 0.0, + "SafeDeceleration": 12.0 + }, + "BehaviorLaneChangeRuleBased": { + "MinRemainingLaneCorridorDistance": 80.0, + "MinVehicleRearDistance": 0.5, + "MinVehicleFrontDistance": 1.0, + "TimeKeepingGap": 0.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 25.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + } + } + } + } + } \ No newline at end of file diff --git a/src/mcts_config/params/sa_mcts.json b/src/mcts_config/params/sa_mcts.json new file mode 100644 index 0000000..e0b63c8 --- /dev/null +++ b/src/mcts_config/params/sa_mcts.json @@ -0,0 +1,74 @@ +{ + "BehaviorRulesMcts": { + "MultiAgent": false, + "MaxNumIterations": 5000, + "RewardVectorSize": 1, + "CooperationFactor": 0.0, + "ReturnLowerBound": [ + -1000.0 + ], + "ReturnUpperBound": [ + 0.0 + ], + "Threshold": [ + 1000000.0 + ], + "UCTExplorationConstant": [1.41], + "Rules": { + "common": [ + { + "formula": "G !collision_ego", + "weight": 0.0, + "priority": 0 + } + ] + }, + "Labels": [], + "PredictionSettings": { + "DefaultModelName": "BehaviorMobilRuleBased", + "DefaultModelParams": { + "BehaviorMobilRuleBased": { + "AThr": 0.2, + "Politeness": 0.0, + "SafeDeceleration": 12.0 + }, + "BehaviorLaneChangeRuleBased": { + "MinRemainingLaneCorridorDistance": 80.0, + "MinVehicleRearDistance": 0.5, + "MinVehicleFrontDistance": 1.0, + "TimeKeepingGap": 0.5 + }, + "BehaviorIDMClassic": { + "MinimumSpacing": 2.0, + "DesiredTimeHeadway": 1.5, + "MaxAcceleration": 1.7000000476837158, + "AccelerationLowerBound": -8.0, + "AccelerationUpperBound": 4.0, + "DesiredVelocity": 10.0, + "ComfortableBrakingAcceleration": 2.0, + "MinVelocity": 0.0, + "MaxVelocity": 50.0, + "Exponent": 4, + "BrakeForLaneEnd": true, + "BrakeForLaneEndEnabledDistance": 60.0, + "BrakeForLaneEndDistanceOffset": 25.0, + "NumTrajectoryTimePoints": 11, + "CoolnessFactor": 0.0 + }, + "BehaviorIDMLaneTracking": { + "CrosstrackErrorGain": 2.5 + } + } + }, + "StateParameters": { + "CollisionWeight": -400.0, + "OutOfMapWeight": -400.0, + "PotentialWeight": 32.0, + "AccelerationWeight": -0.5, + "RadialAccelerationWeight": 0.0, + "DesiredVelocityWeight": -5.0, + "LaneCenterDeviationWeight": 0.0, + "UseRuleRewardForEgoOnly": false + } + } + } \ No newline at end of file diff --git a/src/run/BUILD b/src/run/BUILD new file mode 100644 index 0000000..226bbdf --- /dev/null +++ b/src/run/BUILD @@ -0,0 +1,76 @@ +py_test( + name = "run_benchmark", + srcs = ["run_benchmark.py"], + data = [ + "//src/database:database", + "//src/mcts_config/params:mcts_params", + "//src/viewer_config/params:viewer_params", + "@bark_project//bark/python_wrapper:core.so", + ], + imports = ["../python/"], + deps = [ + "//src/mcts_config", + "//src/traffic_rules:traffic_rules", + "@bark_project//bark/benchmark:benchmark_runner", + "@bark_project//bark/benchmark:benchmark_runner_mp", + "@bark_project//bark/benchmark:benchmark_analyzer", + "@bark_project//bark/runtime/scenario/scenario_generation:scenario_generation", + "@benchmark_database//load:benchmark_database", + "@benchmark_database//serialization:database_serializer", + ], +) + +py_test( + name = "scenario_tuning", + srcs = ["scenario_tuning.py"], + data = ["@bark_project//bark:generate_core", + "//src/database:database", + "//src/mcts_config/params:mcts_params", + "//src/viewer_config/params:viewer_params", + ], + imports = ['../python/'], + deps = ["//src/traffic_rules:traffic_rules", + "@bark_project//bark/benchmark:benchmark_runner", + "@bark_project//bark/benchmark:benchmark_runner_mp", + "@bark_project//bark/benchmark:benchmark_analyzer", + "@bark_project//bark/runtime/scenario/scenario_generation:scenario_generation", + "@benchmark_database//load:benchmark_database", + "@benchmark_database//serialization:database_serializer", + ], +) + +py_test( + name = "merging_test_specific", + srcs = ["merging_test_specific.py"], + data = [ + '@bark_project//bark:generate_core', + "//src/mcts_config/params:mcts_params", + "//src/viewer_config/params:viewer_params", + "//src/database:database"], + imports = ['../python/'], + deps = ["@bark_project//bark/runtime/commons:parameters", + "@bark_project//bark/runtime/commons:xodr_parser", + "@bark_project//bark/runtime/viewer:matplotlib_viewer", + "@bark_project//bark/runtime/scenario/scenario_generation:scenario_generation", + "@bark_project//bark/runtime:runtime", + "//src/mcts_config", + "//src/common:custom_lane_corridor_config"], +) + +py_test( + name = "merging_test_random", + srcs = ["merging_test_random.py"], + data = [ + '@bark_project//bark:generate_core', + "//src/mcts_config/params:mcts_params", + "//src/viewer_config/params:viewer_params", + "//src/database:database"], + imports = ['../python/'], + deps = ["@bark_project//bark/runtime/commons:parameters", + "@bark_project//bark/runtime/commons:xodr_parser", + "@bark_project//bark/runtime/viewer:matplotlib_viewer", + "@bark_project//bark/runtime/scenario/scenario_generation:scenario_generation", + "@bark_project//bark/runtime:runtime", + "//src/mcts_config", + "//src/common:custom_lane_corridor_config"], +) diff --git a/src/run/merging_test_random.py b/src/run/merging_test_random.py new file mode 100644 index 0000000..20d5a29 --- /dev/null +++ b/src/run/merging_test_random.py @@ -0,0 +1,92 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import time +import logging + +from bark.runtime.commons.parameters import ParameterServer +from bark.runtime.viewer.matplotlib_viewer import MPViewer +from bark.runtime.viewer.video_renderer import VideoRenderer +from bark.runtime.scenario.scenario_generation.config_with_ease import \ + ConfigWithEase +from bark.core.models.behavior import * +from bark.core.commons import SetVerboseLevel +from bark.runtime.runtime import Runtime + +from src.mcts_config.mcts_config import create_mcts_configurations +from src.common.custom_lane_corridor_config import CustomLaneCorridorConfig + + +# SetVerboseLevel(5) +logging.getLogger().setLevel(logging.INFO) + +params = ParameterServer() + +params_mobil = ParameterServer( + filename="src/mcts_config/params/mobil.json", log_if_default=True) + +behaviors_tested, params_dict = create_mcts_configurations( + "src/mcts_config/params/", [50], ['sa_mcts']) + +# configure both lanes of the highway. the right lane has one controlled agent +left_lane = CustomLaneCorridorConfig(params=params, + lane_corridor_id=0, + road_ids=[0, 1], + behavior_model=BehaviorMobilRuleBased( + params_mobil), + s_min=10., + s_max=50.) +right_lane = CustomLaneCorridorConfig(params=params, + lane_corridor_id=1, + road_ids=[0, 1], + controlled_ids=True, + behavior_model=behaviors_tested["sa_mcts_50"], + s_min=10., + s_max=30.) + +map_path = "src/database/maps/merging_long_v01.xodr" + +scenarios = \ + ConfigWithEase(num_scenarios=3, + map_file_name=map_path, + random_seed=0, + params=params, + lane_corridor_configs=[left_lane, right_lane]) + +# viewer +params_viewer = ParameterServer( + filename="src/viewer_config/params/mp_viewer_params.json", log_if_default=True) +viewer = MPViewer(params=params_viewer) + +sim_step_time = params["simulation"]["step_time", + "Step-time used in simulation", + 0.25] +sim_real_time_factor = params["simulation"]["real_time_factor", + "execution in real-time or faster", + 1.] + +video_renderer = VideoRenderer(renderer=viewer, + world_step_time=sim_step_time, + fig_path="/tmp/video") + +env = Runtime(step_time=sim_step_time, + viewer=video_renderer, + scenario_generator=scenarios, + render=True) + +n_scenarios = 1 +n_steps = 4 +# run n_scenarios scenarios +for _ in range(0, n_scenarios): + env.reset() + # step each scenario n_steps times + for step in range(0, n_steps): + env.step() + time.sleep(sim_step_time/sim_real_time_factor) + +video_renderer.export_video(filename="/tmp/video", remove_image_dir=False) diff --git a/src/run/merging_test_specific.py b/src/run/merging_test_specific.py new file mode 100644 index 0000000..d49f70f --- /dev/null +++ b/src/run/merging_test_specific.py @@ -0,0 +1,88 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import time +import logging + +from bark.runtime.commons.parameters import ParameterServer +from bark.runtime.viewer.matplotlib_viewer import MPViewer +from bark.runtime.viewer.video_renderer import VideoRenderer +from bark.runtime.scenario.scenario_generation.config_with_ease import \ + ConfigWithEase +from bark.core.models.behavior import * +from bark.runtime.runtime import Runtime + +from src.mcts_config.mcts_config import create_mcts_configurations +from src.common.custom_lane_corridor_config import DeterministicLaneCorridorConfig + + +# SetVerboseLevel(5) +logging.getLogger().setLevel(logging.INFO) + +params = ParameterServer() + +params_mobil = ParameterServer( + filename="src/mcts_config/params/mobil.json", log_if_default=True) + +behaviors_tested, params_dict = create_mcts_configurations( + "src/mcts_config/params/", [50], ['sa_mcts']) + +# configure both lanes of the highway. the right lane has one controlled agent +left_lane = DeterministicLaneCorridorConfig(params=params, + lane_corridor_id=0, + road_ids=[0, 1], + behavior_model=BehaviorMobilRuleBased( + params_mobil), + s_start=[15, 35], + vel_start=10) +right_lane = DeterministicLaneCorridorConfig(params=params, + lane_corridor_id=1, + road_ids=[0, 1], + controlled_ids=True, + behavior_model=behaviors_tested["sa_mcts_50"], + s_start=[15], + vel_start=12) + +map_path = "src/database/maps/merging_long_v01.xodr" + +scenarios = \ + ConfigWithEase(num_scenarios=1, + map_file_name=map_path, + random_seed=0, + params=params, + lane_corridor_configs=[left_lane, right_lane]) + +# viewer +params_viewer = ParameterServer( + filename="src/viewer_config/params/mp_viewer_params.json", log_if_default=True) +viewer = MPViewer(params=params_viewer) + +sim_step_time = params["simulation"]["step_time", + "Step-time used in simulation", + 0.25] +sim_real_time_factor = params["simulation"]["real_time_factor", + "execution in real-time or faster", + 1.] + +video_renderer = VideoRenderer(renderer=viewer, + world_step_time=sim_step_time, + fig_path="/tmp/video") + +env = Runtime(step_time=sim_step_time, + viewer=video_renderer, + scenario_generator=scenarios, + render=True) + +n_steps = 4 +env.reset() +# step scenario n_steps times +for step in range(0, n_steps): + env.step() + time.sleep(sim_step_time/sim_real_time_factor) + +video_renderer.export_video(filename="/tmp/video", remove_image_dir=False) diff --git a/src/run/run_benchmark.py b/src/run/run_benchmark.py new file mode 100644 index 0000000..1cb232d --- /dev/null +++ b/src/run/run_benchmark.py @@ -0,0 +1,106 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import os +import pandas as pd +import logging +import sys + +import matplotlib.pyplot as plt +import matplotlib.gridspec as gridspec + +from bark.runtime.viewer.video_renderer import VideoRenderer +from bark.runtime.viewer.matplotlib_viewer import MPViewer +from bark.benchmark.benchmark_runner import BenchmarkResult, BenchmarkRunner +from bark.benchmark.benchmark_runner_mp import BenchmarkRunnerMP +from bark.runtime.commons.parameters import ParameterServer +from bark.core.commons import SetVerboseLevel +from bark.core.world.evaluation.ltl import * +from bark.core.models.behavior import BehaviorMobilRuleBased +from bark.benchmark.benchmark_analyzer import BenchmarkAnalyzer + +from load.benchmark_database import BenchmarkDatabase +from serialization.database_serializer import DatabaseSerializer + +from src.mcts_config.mcts_config import create_mcts_configurations +from src.traffic_rules.traffic_rules_evaluators import * + +# reduced max steps and scenarios for testing +max_steps = 160 +test_steps = int(max_steps * 0.5 / 0.2) +test_scenarios = 0 # 2 +num_scenarios = 5 + +# set your settingy here, if you do not want ray to use all your system's resources +num_cpus, memory = (6, 10*1000*1024*1024) + +try: + params = ParameterServer( + filename="src/viewer_config/params/mp_viewer_params.json", log_if_default=True) +except: + logging.warning("Cannot find viewer params") + +logging.info("Current Working Directory: {}".format(os.getcwd())) + +if not os.path.exists("src/database"): + print("changing directory") + os.chdir("run_benchmark.runfiles/example_benchmark") + +dbs = DatabaseSerializer(test_scenarios=test_scenarios, + test_world_steps=test_steps, + num_serialize_scenarios=num_scenarios) +dbs.process("src/database", filter_sets="**/*.json") +local_release_filename = dbs.release(version="2021_07_01") + +# reload +db = BenchmarkDatabase(database_root=local_release_filename) + +use_frac_param_from_world = False + +evaluators = {"collision": "EvaluatorCollisionEgoAgent", + "steps": "EvaluatorStepCount", + "out_of_map": "EvaluatorDrivableArea", + "velocity": "EvaluatorVelocity", + "gap": "EvaluatorGapDistanceFront", + "num_agents": "EvaluatorNumberOfAgents", + "safe_distance": get_traffic_rule_evaluator_params("safe_distance"), + "goal_reached": "EvaluatorGoalReached", + } +terminal_when = {"collision": lambda x: x, + "steps": lambda x: x > max_steps, + "goal_reached": lambda x: x, + "out_of_map": lambda x: x} + +behaviors_tested, params_dict = create_mcts_configurations( + "src/mcts_config/params/", [200], ['sa_mcts', 'sa_lex_mcts_sd']) + +paramserver_mobil = ParameterServer( + filename="src/mcts_config/params/mobil.json", log_if_default=True) +behaviors_tested["Mobil"] = BehaviorMobilRuleBased(paramserver_mobil) + +maintain_history = False + +benchmark_runner = BenchmarkRunnerMP(benchmark_database=db, + evaluators=evaluators, + terminal_when=terminal_when, + behaviors=behaviors_tested, + num_scenarios=num_scenarios, + log_eval_avg_every=1, + num_cpus=num_cpus, + memory_total=memory) + +result = benchmark_runner.run(maintain_history=maintain_history) + +print(result.get_data_frame()) + +res_path = os.path.join("./benchmark_results.zip") +result.dump(res_path, max_mb_per_file=20, + dump_histories=maintain_history, dump_configs=False) + +result_loaded = result.load(res_path, load_histories=maintain_history) +print(result.get_data_frame()) diff --git a/src/run/scenario_tuning.py b/src/run/scenario_tuning.py new file mode 100644 index 0000000..693b5bc --- /dev/null +++ b/src/run/scenario_tuning.py @@ -0,0 +1,84 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import os +import pandas as pd +import logging +import sys + +import matplotlib.pyplot as plt +import matplotlib.gridspec as gridspec + +from bark.runtime.viewer.video_renderer import VideoRenderer +from bark.runtime.viewer.matplotlib_viewer import MPViewer +from bark.benchmark.benchmark_runner import BenchmarkResult, BenchmarkRunner +from bark.benchmark.benchmark_runner_mp import BenchmarkRunnerMP +from bark.runtime.commons.parameters import ParameterServer +from bark.core.commons import SetVerboseLevel +from bark.core.world.evaluation.ltl import * +from bark.core.models.behavior import BehaviorMobilRuleBased +from bark.benchmark.benchmark_analyzer import BenchmarkAnalyzer + +from load.benchmark_database import BenchmarkDatabase +from serialization.database_serializer import DatabaseSerializer + +from src.traffic_rules.traffic_rules_evaluators import * + +# reduced max steps and scenarios for testing +max_steps = 160 +test_steps = int(max_steps * 0.5 / 0.2) +test_scenarios = 0 # 2 +num_scenarios = 5 + +try: + params = ParameterServer( + filename="src/viewer_config/params/mp_viewer_params.json", log_if_default=True) +except: + logging.warning("Cannot find viewer params") + +logging.info("Current Working Directory: {}".format(os.getcwd())) + +if not os.path.exists("src/database"): + print("changing directory") + os.chdir("run_benchmark.runfiles/example_benchmark") + +dbs = DatabaseSerializer(test_scenarios=test_scenarios, + test_world_steps=test_steps, + num_serialize_scenarios=num_scenarios) +dbs.process("src/database", filter_sets="**/*.json") +local_release_filename = dbs.release(version="2021_07_01") + +# reload +db = BenchmarkDatabase(database_root=local_release_filename) + +use_frac_param_from_world = False + +evaluators = {"collision": "EvaluatorCollisionEgoAgent", + "steps": "EvaluatorStepCount", + "out_of_map": "EvaluatorDrivableArea", + "safe_distance": get_traffic_rule_evaluator_params("safe_distance"), + "goal_reached": "EvaluatorGoalReached", + } +terminal_when = {"collision": lambda x: x, + "steps": lambda x: x > max_steps, + "goal_reached": lambda x: x, + "out_of_map": lambda x: x} + +paramserver_mobil = ParameterServer( + filename="src/mcts_config/params/mobil.json", log_if_default=True) +behaviors_tested = {"Mobil": BehaviorMobilRuleBased(paramserver_mobil)} + +benchmark_runner = BenchmarkRunner(benchmark_database=db, + evaluators=evaluators, + terminal_when=terminal_when, + behaviors=behaviors_tested, + num_scenarios=num_scenarios, + log_eval_avg_every=1) + +viewer = MPViewer(params=params) +result = benchmark_runner.run(viewer, maintain_history=True) diff --git a/src/traffic_rules/BUILD b/src/traffic_rules/BUILD new file mode 100644 index 0000000..8c04991 --- /dev/null +++ b/src/traffic_rules/BUILD @@ -0,0 +1,7 @@ +py_library( + name = "traffic_rules", + srcs = ["traffic_rules_evaluators.py", + "rule_generation.py",], + data = ["@bark_project//bark/python_wrapper:core.so"], + visibility = ["//visibility:public"], +) diff --git a/src/traffic_rules/rule_generation.py b/src/traffic_rules/rule_generation.py new file mode 100644 index 0000000..e49d39b --- /dev/null +++ b/src/traffic_rules/rule_generation.py @@ -0,0 +1,72 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import logging +import sys +from bark.core.ltl import RuleMonitor +from bark.core.world.evaluation.ltl import * + + +def make_rule_monitors(rule_params): + rules = [] + for rule_param_srv in rule_params: + rules.append(RuleMonitor(rule_param_srv["formula", "Traffic rules described using LTL"], + rule_param_srv["weight", + "Penalty for violating the rule.", 0.0], + rule_param_srv[ + "priority", "Index of the entry in the reward vector to add penalty.", 0])) + + return rules + + +def dump_rules(rules): + rule_str = "" + for agent in rules.keys(): + rule_str = rule_str + "Agent ID: {}".format(agent) + for rule in rules[agent]: + rule_str = rule_str + "\n{}".format(str(rule)) + rule_str = rule_str + "\n\n" + return rule_str + + +def make_SafeDistanceLabelFunction(params): + label_str = params["label_str"] + to_rear = params["to_rear"] + delta_ego = params["delta_ego"] + delta_others = params["delta_others"] + a_e = params["a_e"] + a_o = params["a_o"] + consider_crossing_corridors = params["consider_crossing_corridors"] + max_agents_for_crossing = params["max_agents_for_crossing"] + use_frac_param_from_world = params["use_frac_param_from_world"] + lateral_difference_threshold = params["lateral_difference_threshold"] + check_lateral_dist = params["check_lateral_dist"] + return SafeDistanceLabelFunction(label_str, to_rear, delta_ego, delta_others, a_e, a_o, consider_crossing_corridors, max_agents_for_crossing, use_frac_param_from_world, lateral_difference_threshold, check_lateral_dist) + +def make_CollisionEgoLabelFunction(params): + label_str = params["label_str"] + return CollisionEgoLabelFunction(label_str) + +def _make_default_label(evaluator_name, params): + label_str = params["label_str"] + return eval("{}(label_str)".format(evaluator_name)) + + +def make_labels(label_params): + labels = [] + for label in label_params: + try: + labels.append(eval("make_{}(label)".format(label["type"]))) + except Exception as e: + logging.error("Error during label creation: {}".format(e)) + try: + labels.append(_make_default_label(label["type"], label)) + except Exception as e: + logging.error("Error during label creation: {}".format(e)) + sys.exit(1) + return labels diff --git a/src/traffic_rules/traffic_rules_evaluators.py b/src/traffic_rules/traffic_rules_evaluators.py new file mode 100644 index 0000000..fdd8399 --- /dev/null +++ b/src/traffic_rules/traffic_rules_evaluators.py @@ -0,0 +1,68 @@ +# Copyright (c) 2021 fortiss GmbH +# +# Authors: Julian Bernhard, Klemens Esterle, Patrick Hart and +# Tobias Kessler +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import logging + +from bark.core.world.evaluation.ltl import * + +NOT_AVAILABLE = "Not available, please contact Klemens Esterle: esterle@fortiss.org" + + +def get_traffic_rule_evaluator_params(rule_name): + if rule_name == "safe_distance": + rule = {"type": "EvaluatorLTL", + "params": {"ltl_formula": "G sd_front", + "label_functions": [SafeDistanceLabelFunction("sd_front", False, 1.0, 1.0, -7.84, -7.84, True, 4, False, 2.0, False)]}} + + elif rule_name == "zip_merge": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "right_overtake": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "safe_lane_change": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "safe_lane_change_assumption": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "being_overtaken": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "being_overtaken_assumption": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "speed_advantage_overtaking": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "no_stopping": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "no_stopping_assumption": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "maximum_speed_limit": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "inside_rightmost_lane": + logging.raiseExceptions(NOT_AVAILABLE) + + elif rule_name == "inside_rightmost_lane_assumption": + logging.raiseExceptions(NOT_AVAILABLE) + else: + logging.error("rule has not been defined") + + return rule + + +def get_traffic_rule_evaluator_bark(eval_agent_id, rule_name, location, use_frac_param_from_world): + evaluator_params = get_traffic_rule_evaluator_params( + rule_name, location, use_frac_param_from_world) + evaluator_bark = eval( + "{}(agent_id=eval_agent_id, **evaluator_params['params'])".format(evaluator_params["type"])) + return evaluator_bark diff --git a/src/viewer_config/BUILD b/src/viewer_config/BUILD new file mode 100644 index 0000000..efee9be --- /dev/null +++ b/src/viewer_config/BUILD @@ -0,0 +1,17 @@ +py_library( + name = "viewer_config", + srcs = ["viewer_config.py"], + data = ["@bark_project//bark/python_wrapper:core.so"], + imports = ['../python/'], + deps = ["@bark_project//bark/runtime"], + visibility = ["//visibility:public"], +) + +py_test( + name = "viewer_config_test", + srcs = ["viewer_config_test.py"], + data = ["@bark_project//bark/python_wrapper:core.so", + "//src/viewer_config/params:viewer_params"], + imports = ['../python/'], + deps = [":viewer_config"] +) diff --git a/src/viewer_config/params/BUILD b/src/viewer_config/params/BUILD new file mode 100644 index 0000000..2dd3629 --- /dev/null +++ b/src/viewer_config/params/BUILD @@ -0,0 +1,5 @@ +filegroup( + name="viewer_params", + srcs=glob(["*.json"]), + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/src/viewer_config/params/mp_viewer_description.json b/src/viewer_config/params/mp_viewer_description.json new file mode 100644 index 0000000..eb2cb34 --- /dev/null +++ b/src/viewer_config/params/mp_viewer_description.json @@ -0,0 +1,48 @@ +{ + "Visualization": { + "Agents": { + "Color": { + "Other": { + "Lines": "Color of other agents", + "Face": "Color of other agents" + }, + "Controlled": { + "Lines": "Color of controlled, evaluated agents", + "Face": "Color of controlled, evaluated agents" + }, + "UseColormapForOtherAgents": "Flag to enable color map for other agents", + "IfColormapUseLineColorOthers": "Flag to enable that line color can be fixed for other agents while using colormap" + }, + "Alpha": { + "Controlled": "Alpha of evalagents", + "Other": "Alpha of other agents" + }, + "ColorRoute": "Color of agents routes", + "DrawRoute": "Draw Route of each agent", + "DrawAgentId": "Draw id of each agent", + "DrawBehaviorPlanEvalAgent": "Draw behavior plan of evalauted agent", + "DrawEvalGoals": "Draw Route of eval agent goals", + "EvalGoalColor": "Color of eval agent goals", + "DrawHistory": "Draw history with alpha trace for each agent", + "DrawHistoryDrawFace": "Flag to specify if face is drawn in history mode" + }, + "Map": { + "XodrLanes": { + "Boundaries": { + "Color": "Color of agents except ego vehicle", + "Alpha": "Color of agents except ego vehicle", + "Linewidth": "Linewidth of linestrings" + } + }, + "Plane": { + "Color": "Color of the background plane", + "Alpha": "Alpha of the background plane" + } + }, + "Evaluation": { + "DrawLTLDebugInfo": "Flag to specify if debug info to ltl evaluators shall be plotted", + "DrawRssDebugInfo": "Flag to specify if debug info to rss evaluators shall be plotted", + "DrawRssSafetyResponses": "Flag to specify if visualizating rss safety responses." + } + } +} \ No newline at end of file diff --git a/src/viewer_config/params/mp_viewer_params.json b/src/viewer_config/params/mp_viewer_params.json new file mode 100644 index 0000000..3345a04 --- /dev/null +++ b/src/viewer_config/params/mp_viewer_params.json @@ -0,0 +1,84 @@ +{ + "Visualization": { + "Agents": { + "Color": { + "Other": { + "Lines": [ + 0.1, + 0.1, + 0.1 + ], + "Face": [ + 0.7, + 0.7, + 0.7 + ] + }, + "Controlled": { + "Lines": [ + 0.1, + 0.1, + 0.1 + ], + "Face": [ + 0.9, + 0, + 0 + ] + }, + "UseColormapForOtherAgents": true, + "IfColormapUseLineColorOthers": true + }, + "Alpha": { + "Controlled": 0.8, + "Other": 0.8 + }, + "ColorRoute": [ + 0.2, + 0.2, + 0.2 + ], + "DrawRoute": false, + "DrawAgentId": true, + "DrawInvalidAgents": true, + "DrawBehaviorPlanEvalAgent": true, + "DrawOrientationArrow": false, + "DrawEvalGoals": false, + "EvalGoalColor": [ + 0.49, + 0.63, + 0.83 + ], + "DrawHistory": true, + "DrawHistoryDrawFace": false + }, + "Map": { + "XodrLanes": { + "Boundaries": { + "Color": [ + 0.7, + 0.7, + 0.7 + ], + "Alpha": 1.0, + "Linewidth": 1.0 + } + }, + "Plane": { + "Color": [ + 1, + 1, + 1, + 1 + ], + "Alpha": 1.0 + }, + "DrawAerialImage": true + }, + "Evaluation": { + "DrawLTLDebugInfo": false, + "DrawRssDebugInfo": false, + "DrawRssSafetyResponses": false + } + } +} \ No newline at end of file diff --git a/src/viewer_config/viewer_config.py b/src/viewer_config/viewer_config.py new file mode 100644 index 0000000..d0d5fa7 --- /dev/null +++ b/src/viewer_config/viewer_config.py @@ -0,0 +1,13 @@ +import os + +from bark.runtime.viewer.matplotlib_viewer import MPViewer +from bark.runtime.commons.parameters import ParameterServer + + +def dump_viewer_default_params(dir): + params = ParameterServer() + miqp_behavior = MPViewer(params) + + params.Save(filename=os.path.join(dir, "mp_viewer_params.json")) + params.Save(filename=os.path.join(dir, "mp_viewer_description.json"), + print_description=True) diff --git a/src/viewer_config/viewer_config_test.py b/src/viewer_config/viewer_config_test.py new file mode 100644 index 0000000..675f651 --- /dev/null +++ b/src/viewer_config/viewer_config_test.py @@ -0,0 +1,19 @@ +import unittest +import pickle + +from bark.runtime.commons.parameters import ParameterServer + +from src.viewer_config.viewer_config import dump_viewer_default_params + + +def pickle_unpickle(object): + d = pickle.dumps(object) + return pickle.loads(d) + + +class ViewerTests(unittest.TestCase): + def test_dump_defaults(self): + dump_viewer_default_params("/tmp/") + +if __name__ == '__main__': + unittest.main() diff --git a/tools/BUILD b/tools/BUILD new file mode 100644 index 0000000..e69de29 diff --git a/tools/deps.bzl b/tools/deps.bzl new file mode 100644 index 0000000..fafe16a --- /dev/null +++ b/tools/deps.bzl @@ -0,0 +1,28 @@ +load("@bazel_tools//tools/build_defs/repo:git.bzl", "git_repository") +load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive", "http_file") + +def example_benchmark_dependencies(): + _maybe( + git_repository, + name = "rule_monitor_project", + commit = "187c125a18979214d638ca771dd86e7934932b94", + remote = "https://github.com/bark-simulator/rule-monitoring.git", + ) + + _maybe( + git_repository, + name = "planner_rules_mcts", + commit = "35b09a857d8c3f1c65e0ed80ee4df1b358e45bf4", + remote = "https://github.com/bark-simulator/planner-rules-mcts.git", + ) + + _maybe( + git_repository, + name = "bark_project", + commit = "4e33a66ec5dc6a936a71cad1bc0db1807a9b7cb6", + remote = "https://github.com/bark-simulator/bark.git", + ) + +def _maybe(repo_rule, name, **kwargs): + if name not in native.existing_rules(): + repo_rule(name = name, **kwargs) diff --git a/tools/python/BUILD b/tools/python/BUILD new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/tools/python/BUILD @@ -0,0 +1 @@ + diff --git a/tools/python/into_venv.sh b/tools/python/into_venv.sh new file mode 100644 index 0000000..002f5b2 --- /dev/null +++ b/tools/python/into_venv.sh @@ -0,0 +1,3 @@ +#!/bin/bash +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" +source $DIR/venv/bin/activate diff --git a/tools/python/requirements.txt b/tools/python/requirements.txt new file mode 100644 index 0000000..57a94fd --- /dev/null +++ b/tools/python/requirements.txt @@ -0,0 +1,22 @@ +matplotlib==3.4.2 +numpy==1.21.0 +pandas==1.2.5 +psutil==5.8.0 +ray==0.7.6 +seaborn==0.11.0 +jsonpickle==2.0 +paramiko==2.7.0 +colour==0.1.5 +lxml==4.6.3 +scipy==1.7.0 +sphinx==4.0.2 +recommonmark==0.7.1 +sphinx_rtd_theme==0.5.2 +autopep8==1.5.7 +cpplint==1.5.5 +pygame==2.0.1 +panda3d==1.10.9 +aabbtree==2.8.0 +notebook==6.4.0 +jupyter==1.0.0 +ipython==7.25.0 \ No newline at end of file diff --git a/tools/python/setup_venv.sh b/tools/python/setup_venv.sh new file mode 100644 index 0000000..6e38e38 --- /dev/null +++ b/tools/python/setup_venv.sh @@ -0,0 +1,5 @@ +#!/bin/bash +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" +mkdir -p $DIR/venv +virtualenv --system-site-packages -p python3.7 $DIR/venv +source $DIR/venv/bin/activate && pip3 install -r $DIR/requirements.txt