diff --git a/vrx_gz/models/obstacle_course/model.config b/vrx_gz/models/obstacle_course0/model.config similarity index 100% rename from vrx_gz/models/obstacle_course/model.config rename to vrx_gz/models/obstacle_course0/model.config diff --git a/vrx_gz/models/obstacle_course/model.sdf b/vrx_gz/models/obstacle_course0/model.sdf similarity index 99% rename from vrx_gz/models/obstacle_course/model.sdf rename to vrx_gz/models/obstacle_course0/model.sdf index 40a14f916..0a5af5d94 100644 --- a/vrx_gz/models/obstacle_course/model.sdf +++ b/vrx_gz/models/obstacle_course0/model.sdf @@ -1,6 +1,4 @@ - - diff --git a/vrx_gz/models/obstacle_course1/model.config b/vrx_gz/models/obstacle_course1/model.config new file mode 100644 index 000000000..c059adbb0 --- /dev/null +++ b/vrx_gz/models/obstacle_course1/model.config @@ -0,0 +1,13 @@ + + + obstacle_course + 1.0 + model.sdf + + Carlos Agüero + caguero@openrobotics.org + + + An obstacle field. + + diff --git a/vrx_gz/models/obstacle_course1/model.sdf b/vrx_gz/models/obstacle_course1/model.sdf new file mode 100644 index 000000000..d82c59999 --- /dev/null +++ b/vrx_gz/models/obstacle_course1/model.sdf @@ -0,0 +1,575 @@ + + + + + mb_round_buoy_black_0 + 11.75309579 -44.04348694 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_1 + -4.38017291 -31.00932693 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_2 + 22.6568676 -0.92141124 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_3 + 44.09486489 5.66663984 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_4 + 32.17463149 -15.94637324 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_5 + -6.94456804 -2.61300114 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_6 + -50.40281825 -61.06834745 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_7 + 24.576913737 30.3481238647 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_8 + 37.5737439619 -18.8335819857 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_9 + -2.49572219989 13.1619102364 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_0 + -22.30202998 7.58586649 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_1 + 33.86021685 14.50500992 0.0 0 0 0 + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + + + mb_round_buoy_orange_2 + -37.1237799886 -55.0780758672 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_3 + -23.77126376 27.34241072 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_4 + -16.29351304 -24.97527506 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + diff --git a/vrx_gz/models/obstacle_course2/model.config b/vrx_gz/models/obstacle_course2/model.config new file mode 100644 index 000000000..c059adbb0 --- /dev/null +++ b/vrx_gz/models/obstacle_course2/model.config @@ -0,0 +1,13 @@ + + + obstacle_course + 1.0 + model.sdf + + Carlos Agüero + caguero@openrobotics.org + + + An obstacle field. + + diff --git a/vrx_gz/models/obstacle_course2/model.sdf b/vrx_gz/models/obstacle_course2/model.sdf new file mode 100644 index 000000000..56e639b50 --- /dev/null +++ b/vrx_gz/models/obstacle_course2/model.sdf @@ -0,0 +1,727 @@ + + + + + mb_round_buoy_black_0 + -13.95491156 -25.35449915 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_1 + 7.71587819 37.31995694 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_2 + -6.69036446 18.26817426 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_3 + 31.12515658 -8.04971514 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_4 + -51.65027868 -6.04370199 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_5 + 28.05545934 19.39557671 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_6 + 46.2135293014 -5.59469145311 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_7 + -23.57401351 -8.88047873 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_8 + -12.96886565 -47.10898357 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_9 + 13.81544835 -5.73134056 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_10 + -3.65783836 -17.10255278 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_black_11 + 41.18085609 24.4716514 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_0 + 32.80793763 2.60427048 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_1 + -68.93127611 -42.07725144 0.0 0 0 0 + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + + + mb_round_buoy_orange_2 + -13.17598349 0.55872345 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_3 + -14.90379316 -46.16465368 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_4 + 17.89343713 -18.0378292 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_5 + 31.84129529 2.48724042 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + mb_round_buoy_orange_6 + 46.90593789 -64.26964395 0.0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 0 0 0 0 + + + 0.25 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + diff --git a/vrx_gz/models/short_navigation_course_1/model.config b/vrx_gz/models/short_navigation_course_1/model.config new file mode 100644 index 000000000..41fcdc10b --- /dev/null +++ b/vrx_gz/models/short_navigation_course_1/model.config @@ -0,0 +1,13 @@ + + + short_navigation_course_0 + 1.0 + model.sdf + + Carlos Aguero + caguero@openrobotics.org + + + A short navigation course. + + diff --git a/vrx_gz/models/short_navigation_course_1/model.sdf b/vrx_gz/models/short_navigation_course_1/model.sdf new file mode 100644 index 000000000..38e26152a --- /dev/null +++ b/vrx_gz/models/short_navigation_course_1/model.sdf @@ -0,0 +1,335 @@ + + + + + + + + red_bound_0 + 0 12 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_1 + -20 0 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_2 + -34 -6 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_3 + -44 4 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + + green_bound_0 + 0 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_white + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_1 + -10 -10 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_green + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_2 + -36 -18 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_green + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_3 + -58 4 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + diff --git a/vrx_gz/models/short_navigation_course_2/model.config b/vrx_gz/models/short_navigation_course_2/model.config new file mode 100644 index 000000000..41fcdc10b --- /dev/null +++ b/vrx_gz/models/short_navigation_course_2/model.config @@ -0,0 +1,13 @@ + + + short_navigation_course_0 + 1.0 + model.sdf + + Carlos Aguero + caguero@openrobotics.org + + + A short navigation course. + + diff --git a/vrx_gz/models/short_navigation_course_2/model.sdf b/vrx_gz/models/short_navigation_course_2/model.sdf new file mode 100644 index 000000000..22d1ab271 --- /dev/null +++ b/vrx_gz/models/short_navigation_course_2/model.sdf @@ -0,0 +1,335 @@ + + + + + + + + red_bound_0 + 0 12 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_1 + -20 22 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_2 + -40 0 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + red_bound_3 + -60 12 0 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_red + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + + green_bound_0 + 0 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_white + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_1 + -20 -12 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_green + + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_2 + -40 -10 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_green + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + green_bound_3 + -60 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/mb_marker_buoy_black + + 1000 + 0.0 + 25.0 + 2.0 + + link + 0 0 -0.3 0 0 0 + + + 0.325 + 0.1 + + + + + 1000 1000 + 50 50> + + PMS + 5.0 + 3 + 1.1 + 0.3 + 1 0 + 0.4 + 2.0 + 0.0 + 0.0 + + + + + + + + diff --git a/vrx_gz/src/ScoringPlugin.cc b/vrx_gz/src/ScoringPlugin.cc index 8b94c7f95..2e5c74356 100644 --- a/vrx_gz/src/ScoringPlugin.cc +++ b/vrx_gz/src/ScoringPlugin.cc @@ -170,6 +170,9 @@ class ScoringPlugin::Implementation /// \brief Event manager for exiting the simulation. public: sim::EventManager *eventManager{nullptr}; + + /// \brief Whether we have announced the VRX_EXIT_ON_COMPLETION warning. + public: bool exitWarningAnnounced = false; }; ////////////////////////////////////////////////// @@ -354,11 +357,12 @@ void ScoringPlugin::Implementation::Exit() // shutdown gazebo this->eventManager->Emit(); } - else + else if (!this->exitWarningAnnounced) { gzerr << "VRX_EXIT_ON_COMPLETION and " << "both not set, will not shutdown on ScoringPlugin::Exit()" << std::endl; + this->exitWarningAnnounced = true; } return; } diff --git a/vrx_gz/src/vrx_gz/launch.py b/vrx_gz/src/vrx_gz/launch.py index d645a24c9..7168690d2 100644 --- a/vrx_gz/src/vrx_gz/launch.py +++ b/vrx_gz/src/vrx_gz/launch.py @@ -31,7 +31,10 @@ import os GYMKHANA_WORLDS = [ - 'gymkhana_task' + 'gymkhana_task', + 'practice_2022_gymkhana0_task', + 'practice_2022_gymkhana1_task', + 'practice_2022_gymkhana2_task' ] PERCEPTION_WORLDS = [ diff --git a/vrx_gz/worlds/2022_practice/practice_2022_gymkhana0_task.sdf b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana0_task.sdf new file mode 100644 index 000000000..d457b42ac --- /dev/null +++ b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana0_task.sdf @@ -0,0 +1,532 @@ + + + + + + + 0.004 + 1.0 + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -478.1 148.2 13.2 0 0.25 2.94 + + 0.25 + 10000 + + + + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + + false + 5 + 5 + floating + false + + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + true + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + + false + 0 + 0 + 250 + 50 + floating + false + #666666 + + + + + + + false + 250 + 0 + 150 + 50 + floating + false + #666666 + + + + + + + false + 0 + 50 + 250 + 50 + floating + false + #777777 + + + + false + + + + + + false + 250 + 50 + 50 + 50 + floating + false + #777777 + + + + + + + false + 300 + 50 + 50 + 50 + floating + false + #777777 + + + + true + true + 4000000 + + + + false + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + false + + + + + + + + + + ogre2 + true + + + + + + + + + + + + + + + + + + false + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + + EARTH_WGS84 + ENU + -33.724223 + 150.679736 + 0.0 + 0.0 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + 0 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/sydney_regatta + + + + Coast Waves + 0 0 0 0 0 0 + coast_waves + + + + platform + platform + + + + + model://short_navigation_course_0 + -524 186 0 0 0 -1.44 + + + + + buoys + model://obstacle_course0 + -477 275 0 0 0 -2.54 + + + + + post_0 + -535.916809 154.362869 0.675884 -0.17182 0.030464 -0.005286 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_1 + -527.48999 153.854782 0.425844 -0.1365 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_2 + -544.832825 156.671951 0.499025 -0.162625 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + + + -531.063721 147.668579 1.59471 -0.068142 0 -0.1 + https://fuel.gazebosim.org/1.0/openrobotics/models/antenna + + + + + ground_station_0 + -540.796448 146.493744 1.671421 -0.00834 0.01824 1.301726 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_1 + -537.622681 145.827896 1.681931 -0.00603 0.018667 1.301571 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_2 + -534.550537 144.910400 1.720474 -0.004994 0.020798 1.301492 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + + 0 0 0 + + + + + 0.002 + + + 10 + + 0.05 + 60 + + + 0 + 0.0002 + + + + 30 + + 5 + 20 + + + 0 + 0.03 + + + + + + 0 + 0.03 + + + + + + + wamv + gymkhana + /vrx/task/info + /vrx/debug/contact + 10 + 10 + 300 + + true + 1 + /wamv/pingers/pinger/set_pinger_position + -503 302.5 0 + + + + + wamv + gymkhana_channel + /vrx/gymkhana_channel/task/info + /vrx/gymkhana_channel/debug/contact + + false + + 10 + 10 + 300 + 10 + /vrx/release + + short_navigation_course_0 + 10.0 + + + red_bound_0 + green_bound_0 + + + red_bound_1 + green_bound_1 + + + red_bound_2 + green_bound_2 + + + true + + + + + wamv + gymkhana_blackbox + /vrx/gymkhana_blackbox/mean_pose_error + /vrx/gymkhana_blackbox/pose_error + /vrx/gymkhana_blackbox/goal + /vrx/gymkhana_blackbox/task/info + /vrx/gymkhana_blackbox/debug/contact + + false + + false + -503 302.5 0 + 10 + 10 + 300 + /vrx/release + true + + + + diff --git a/vrx_gz/worlds/2022_practice/practice_2022_gymkhana1_task.sdf b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana1_task.sdf new file mode 100644 index 000000000..b9d6dabf4 --- /dev/null +++ b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana1_task.sdf @@ -0,0 +1,532 @@ + + + + + + + 0.004 + 1.0 + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -478.1 148.2 13.2 0 0.25 2.94 + + 0.25 + 10000 + + + + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + + false + 5 + 5 + floating + false + + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + true + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + + false + 0 + 0 + 250 + 50 + floating + false + #666666 + + + + + + + false + 250 + 0 + 150 + 50 + floating + false + #666666 + + + + + + + false + 0 + 50 + 250 + 50 + floating + false + #777777 + + + + false + + + + + + false + 250 + 50 + 50 + 50 + floating + false + #777777 + + + + + + + false + 300 + 50 + 50 + 50 + floating + false + #777777 + + + + true + true + 4000000 + + + + false + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + false + + + + + + + + + + ogre2 + true + + + + + + + + + + + + + + + + + + false + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + + EARTH_WGS84 + ENU + -33.724223 + 150.679736 + 0.0 + 0.0 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + 0 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/sydney_regatta + + + + Coast Waves + 0 0 0 0 0 0 + coast_waves + + + + platform + platform + + + + + model://short_navigation_course_1 + -535 180 0 0 0 -1.44 + + + + + buoys + model://obstacle_course1 + -500 250 0 0 0 0.44 + + + + + post_0 + -535.916809 154.362869 0.675884 -0.17182 0.030464 -0.005286 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_1 + -527.48999 153.854782 0.425844 -0.1365 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_2 + -544.832825 156.671951 0.499025 -0.162625 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + + + -531.063721 147.668579 1.59471 -0.068142 0 -0.1 + https://fuel.gazebosim.org/1.0/openrobotics/models/antenna + + + + + ground_station_0 + -540.796448 146.493744 1.671421 -0.00834 0.01824 1.301726 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_1 + -537.622681 145.827896 1.681931 -0.00603 0.018667 1.301571 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_2 + -534.550537 144.910400 1.720474 -0.004994 0.020798 1.301492 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + + 0 0 0 + + + + + 0.002 + + + 10 + + 0.05 + 60 + + + 0 + 0.0002 + + + + 30 + + 5 + 20 + + + 0 + 0.03 + + + + + + 0 + 0.03 + + + + + + + wamv + gymkhana + /vrx/task/info + /vrx/debug/contact + 10 + 10 + 300 + + true + 1 + /wamv/pingers/pinger/set_pinger_position + -495 265 0 + + + + + wamv + gymkhana_channel + /vrx/gymkhana_channel/task/info + /vrx/gymkhana_channel/debug/contact + + false + + 10 + 10 + 300 + 10 + /vrx/release + + short_navigation_course_0 + 10.0 + + + red_bound_0 + green_bound_0 + + + red_bound_1 + green_bound_1 + + + red_bound_2 + green_bound_2 + + + true + + + + + wamv + gymkhana_blackbox + /vrx/gymkhana_blackbox/mean_pose_error + /vrx/gymkhana_blackbox/pose_error + /vrx/gymkhana_blackbox/goal + /vrx/gymkhana_blackbox/task/info + /vrx/gymkhana_blackbox/debug/contact + + false + + false + -495 265 0 + 10 + 10 + 300 + /vrx/release + true + + + + diff --git a/vrx_gz/worlds/2022_practice/practice_2022_gymkhana2_task.sdf b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana2_task.sdf new file mode 100644 index 000000000..35a5a4116 --- /dev/null +++ b/vrx_gz/worlds/2022_practice/practice_2022_gymkhana2_task.sdf @@ -0,0 +1,532 @@ + + + + + + + 0.004 + 1.0 + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -478.1 148.2 13.2 0 0.25 2.94 + + 0.25 + 10000 + + + + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + + + + false + 5 + 5 + floating + false + + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + true + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + + false + 0 + 0 + 250 + 50 + floating + false + #666666 + + + + + + + false + 250 + 0 + 150 + 50 + floating + false + #666666 + + + + + + + false + 0 + 50 + 250 + 50 + floating + false + #777777 + + + + false + + + + + + false + 250 + 50 + 50 + 50 + floating + false + #777777 + + + + + + + false + 300 + 50 + 50 + 50 + floating + false + #777777 + + + + true + true + 4000000 + + + + false + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + + + + docked_collapsed + + + + false + + + + + + + + + + ogre2 + true + + + + + + + + + + + + + + + + + + false + 1.0 1.0 1.0 + 0.8 0.8 0.8 + + + + + EARTH_WGS84 + ENU + -33.724223 + 150.679736 + 0.0 + 0.0 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + 0 0 0.2 0 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/sydney_regatta + + + + Coast Waves + 0 0 0 0 0 0 + coast_waves + + + + platform + platform + + + + + model://short_navigation_course_2 + -524 186 0 0 0 -1.44 + + + + + buoys + model://obstacle_course2 + -530 290 0 0 0 1.17 + + + + + post_0 + -535.916809 154.362869 0.675884 -0.17182 0.030464 -0.005286 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_1 + -527.48999 153.854782 0.425844 -0.1365 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + post_2 + -544.832825 156.671951 0.499025 -0.162625 0 0 + https://fuel.gazebosim.org/1.0/openrobotics/models/post + + + + + -531.063721 147.668579 1.59471 -0.068142 0 -0.1 + https://fuel.gazebosim.org/1.0/openrobotics/models/antenna + + + + + ground_station_0 + -540.796448 146.493744 1.671421 -0.00834 0.01824 1.301726 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_1 + -537.622681 145.827896 1.681931 -0.00603 0.018667 1.301571 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + ground_station_2 + -534.550537 144.910400 1.720474 -0.004994 0.020798 1.301492 + https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station + + + + 0 0 0 + + + + + 0.002 + + + 10 + + 0.05 + 60 + + + 0 + 0.0002 + + + + 30 + + 5 + 20 + + + 0 + 0.03 + + + + + + 0 + 0.03 + + + + + + + wamv + gymkhana + /vrx/task/info + /vrx/debug/contact + 10 + 10 + 300 + + true + 1 + /wamv/pingers/pinger/set_pinger_position + -533 293 0 + + + + + wamv + gymkhana_channel + /vrx/gymkhana_channel/task/info + /vrx/gymkhana_channel/debug/contact + + false + + 10 + 10 + 300 + 10 + /vrx/release + + short_navigation_course_0 + 10.0 + + + red_bound_0 + green_bound_0 + + + red_bound_1 + green_bound_1 + + + red_bound_2 + green_bound_2 + + + true + + + + + wamv + gymkhana_blackbox + /vrx/gymkhana_blackbox/mean_pose_error + /vrx/gymkhana_blackbox/pose_error + /vrx/gymkhana_blackbox/goal + /vrx/gymkhana_blackbox/task/info + /vrx/gymkhana_blackbox/debug/contact + + false + + false + -533 293 0 + 10 + 10 + 300 + /vrx/release + true + + + + diff --git a/vrx_gz/worlds/gymkhana_task.sdf b/vrx_gz/worlds/gymkhana_task.sdf index 51498a420..d3c3251bb 100644 --- a/vrx_gz/worlds/gymkhana_task.sdf +++ b/vrx_gz/worlds/gymkhana_task.sdf @@ -365,7 +365,7 @@ buoys - model://obstacle_course + model://obstacle_course0 -477 275 0 0 0 2.54 @@ -409,13 +409,6 @@ https://fuel.gazebosim.org/1.0/openrobotics/models/ground_station - - - 0 0 0