diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp index 04d07462e8695..5742e6b5d1872 100644 --- a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp +++ b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp @@ -728,10 +728,10 @@ void calc_2d_bounding_box_bottom_orientation_line_list( // front corner cuts for orientation const double point_list[4][3] = { - {length_half, width_half - tick_width, height_half}, - {length_half - tick_length, width_half, height_half}, - {length_half, -width_half + tick_width, height_half}, - {length_half - tick_length, -width_half, height_half}, + {length_half, width_half - tick_width, -height_half}, + {length_half - tick_length, width_half, -height_half}, + {length_half, -width_half + tick_width, -height_half}, + {length_half - tick_length, -width_half, -height_half}, }; const int point_pairs[2][2] = { {0, 1}, diff --git a/common/autoware_pyplot/CMakeLists.txt b/common/autoware_pyplot/CMakeLists.txt new file mode 100644 index 0000000000000..6922d5d9306f7 --- /dev/null +++ b/common/autoware_pyplot/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 3.14) + +project(autoware_pyplot) + +find_package(autoware_cmake REQUIRED) + +find_package( + Python3 + COMPONENTS Interpreter Development + REQUIRED) +find_package(pybind11 REQUIRED) + +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} STATIC + DIRECTORY src +) +target_link_libraries(${PROJECT_NAME} ${Python3_LIBRARIES} pybind11::embed) + +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + + file(GLOB_RECURSE test_files test/*.cpp) + + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${test_files}) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) +endif() + +ament_auto_package() diff --git a/common/autoware_pyplot/include/autoware/pyplot/axes.hpp b/common/autoware_pyplot/include/autoware/pyplot/axes.hpp new file mode 100644 index 0000000000000..53eb2daf21b8f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/axes.hpp @@ -0,0 +1,141 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__AXES_HPP_ +#define AUTOWARE__PYPLOT__AXES_HPP_ + +#include +#include +#include + +#include + +namespace autoware::pyplot +{ +inline namespace axes +{ +class DECL_VISIBILITY Axes : public PyObjectWrapper +{ +public: + explicit Axes(const pybind11::object & object); + explicit Axes(pybind11::object && object); + + PyObjectWrapper add_patch( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper bar_label( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper cla( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper contour( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper errorbar( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper fill( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper fill_between( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + std::tuple get_xlim() const; + + std::tuple get_ylim() const; + + PyObjectWrapper grid( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper imshow( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + legend::Legend legend( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper plot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + quiver::Quiver quiver( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_aspect( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_title( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_xlabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_xlim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_ylabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_ylim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper text( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + + pybind11::object add_patch_attr; + pybind11::object cla_attr; + pybind11::object contour_attr; + pybind11::object contourf_attr; + pybind11::object fill_attr; + pybind11::object fill_between_attr; + pybind11::object get_xlim_attr; + pybind11::object get_ylim_attr; + pybind11::object grid_attr; + pybind11::object imshow_attr; + pybind11::object legend_attr; + pybind11::object quiver_attr; + pybind11::object plot_attr; + pybind11::object scatter_attr; + pybind11::object set_aspect_attr; + pybind11::object set_title_attr; + pybind11::object set_xlabel_attr; + pybind11::object set_xlim_attr; + pybind11::object set_ylabel_attr; + pybind11::object set_ylim_attr; + pybind11::object text_attr; +}; +} // namespace axes +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__AXES_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/common.hpp b/common/autoware_pyplot/include/autoware/pyplot/common.hpp new file mode 100644 index 0000000000000..123bd82029e08 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/common.hpp @@ -0,0 +1,44 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__COMMON_HPP_ +#define AUTOWARE__PYPLOT__COMMON_HPP_ + +#include + +namespace autoware::pyplot +{ + +#ifdef _WIN32 +#define DECL_VISIBILITY __declspec(dllexport) +#else +#define DECL_VISIBILITY __attribute__((visibility("hidden"))) +#endif + +inline namespace common +{ +class DECL_VISIBILITY PyObjectWrapper +{ +public: + explicit PyObjectWrapper(const pybind11::object & object); + explicit PyObjectWrapper(pybind11::object && object); + pybind11::object unwrap() const { return self_; } + +protected: + pybind11::object self_; +}; +} // namespace common +} // namespace autoware::pyplot + +#endif // AUTOWARE__PYPLOT__COMMON_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/figure.hpp b/common/autoware_pyplot/include/autoware/pyplot/figure.hpp new file mode 100644 index 0000000000000..d438682d5b368 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/figure.hpp @@ -0,0 +1,62 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__FIGURE_HPP_ +#define AUTOWARE__PYPLOT__FIGURE_HPP_ + +#include +#include + +namespace autoware::pyplot +{ +inline namespace figure +{ +class DECL_VISIBILITY Figure : public PyObjectWrapper +{ +public: + explicit Figure(const pybind11::object & object); + explicit Figure(pybind11::object && object); + + axes::Axes add_axes( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + axes::Axes add_subplot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper colorbar( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper savefig( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper tight_layout( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + + pybind11::object add_axes_attr; + pybind11::object add_subplot_attr; + pybind11::object colorbar_attr; + pybind11::object savefig_attr; + pybind11::object tight_layout_attr; +}; +} // namespace figure +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__FIGURE_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/legend.hpp b/common/autoware_pyplot/include/autoware/pyplot/legend.hpp new file mode 100644 index 0000000000000..853f1e288407c --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/legend.hpp @@ -0,0 +1,32 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__LEGEND_HPP_ +#define AUTOWARE__PYPLOT__LEGEND_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace legend +{ +class DECL_VISIBILITY Legend : public PyObjectWrapper +{ +public: + explicit Legend(const pybind11::object & object); + explicit Legend(pybind11::object && object); +}; +} // namespace legend +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__LEGEND_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/loader.hpp b/common/autoware_pyplot/include/autoware/pyplot/loader.hpp new file mode 100644 index 0000000000000..df44c257d5925 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/loader.hpp @@ -0,0 +1,28 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__LOADER_HPP_ +#define AUTOWARE__PYPLOT__LOADER_HPP_ + +namespace autoware::pyplot +{ + +#define LOAD_FUNC_ATTR(obj, mod) \ + do { \ + obj##_attr = mod.attr(#obj); \ + } while (0) + +} // namespace autoware::pyplot + +#endif // AUTOWARE__PYPLOT__LOADER_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/patches.hpp b/common/autoware_pyplot/include/autoware/pyplot/patches.hpp new file mode 100644 index 0000000000000..0c6c545942c74 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/patches.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__PATCHES_HPP_ +#define AUTOWARE__PYPLOT__PATCHES_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace patches +{ +class DECL_VISIBILITY Circle : public PyObjectWrapper +{ +public: + explicit Circle( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Ellipse : public PyObjectWrapper +{ +public: + explicit Ellipse( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Rectangle : public PyObjectWrapper +{ +public: + explicit Rectangle( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Polygon : public PyObjectWrapper +{ +public: + explicit Polygon( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; +} // namespace patches +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__PATCHES_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp b/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp new file mode 100644 index 0000000000000..83e0febeb237f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp @@ -0,0 +1,164 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__PYPLOT_HPP_ +#define AUTOWARE__PYPLOT__PYPLOT_HPP_ + +#include +#include +#include + +#include +#include +#include + +namespace autoware::pyplot +{ +struct DECL_VISIBILITY PyPlot +{ +public: + explicit PyPlot(const pybind11::module & mod_); + + axes::Axes axes(const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper axis( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper cla( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper clf( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + figure::Figure figure( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + axes::Axes gca( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + figure::Figure gcf( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper gci( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper grid( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper imshow( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper legend( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper plot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper quiver( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper savefig( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper scatter( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper show( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + axes::Axes subplot(const pybind11::dict & kwargs = pybind11::dict()); + axes::Axes subplot(int cri); + + std::tuple subplots(const pybind11::dict & kwargs = pybind11::dict()); + std::tuple> subplots( + int r, int c, const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper title( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper xlabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper xlim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper ylabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper ylim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + +private: + void load_attrs(); + pybind11::module mod; + pybind11::object axes_attr; + pybind11::object cla_attr; + pybind11::object clf_attr; + pybind11::object figure_attr; + pybind11::object gca_attr; + pybind11::object gcf_attr; + pybind11::object gci_attr; + pybind11::object grid_attr; + pybind11::object imshow_attr; + pybind11::object legend_attr; + pybind11::object plot_attr; + pybind11::object quiver_attr; + pybind11::object savefig_attr; + pybind11::object scatter_attr; + pybind11::object show_attr; + pybind11::object subplot_attr; + pybind11::object subplots_attr; + pybind11::object title_attr; + pybind11::object xlabel_attr; + pybind11::object xlim_attr; + pybind11::object ylabel_attr; + pybind11::object ylim_attr; +}; + +PyPlot import(); + +} // namespace autoware::pyplot + +template +pybind11::tuple Args(ArgsT &&... args) +{ + return pybind11::make_tuple(std::forward(args)...); +} + +using Kwargs = pybind11::dict; + +namespace py = pybind11; +using namespace py::literals; + +#endif // AUTOWARE__PYPLOT__PYPLOT_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp b/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp new file mode 100644 index 0000000000000..443c0540d9308 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp @@ -0,0 +1,32 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__QUIVER_HPP_ +#define AUTOWARE__PYPLOT__QUIVER_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace quiver +{ +class DECL_VISIBILITY Quiver : public PyObjectWrapper +{ +public: + explicit Quiver(const pybind11::object & object); + explicit Quiver(pybind11::object && object); +}; +} // namespace quiver +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__QUIVER_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/text.hpp b/common/autoware_pyplot/include/autoware/pyplot/text.hpp new file mode 100644 index 0000000000000..27f892e90488f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/text.hpp @@ -0,0 +1,40 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE__PYPLOT__TEXT_HPP_ +#define AUTOWARE__PYPLOT__TEXT_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace text +{ +class DECL_VISIBILITY Text : public PyObjectWrapper +{ +public: + explicit Text(const pybind11::object & object); + explicit Text(pybind11::object && object); + + PyObjectWrapper set_rotation( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + pybind11::object set_rotation_attr; +}; +} // namespace text +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__TEXT_HPP_ diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml new file mode 100644 index 0000000000000..1391db88cddff --- /dev/null +++ b/common/autoware_pyplot/package.xml @@ -0,0 +1,25 @@ + + + + autoware_pyplot + 0.1.0 + C++ interface for matplotlib based on pybind11 + Mamoru Sobue + Yukinari Hisaki + Apache License 2.0 + + Mamoru Sobue + + ament_cmake_auto + autoware_cmake + + pybind11-dev + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/common/autoware_pyplot/src/axes.cpp b/common/autoware_pyplot/src/axes.cpp new file mode 100644 index 0000000000000..0f08ffe5773f6 --- /dev/null +++ b/common/autoware_pyplot/src/axes.cpp @@ -0,0 +1,154 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace autoware::pyplot +{ +inline namespace axes +{ +Axes::Axes(const pybind11::object & object) : PyObjectWrapper(object) +{ + load_attrs(); +} +Axes::Axes(pybind11::object && object) : PyObjectWrapper(object) +{ + load_attrs(); +} + +PyObjectWrapper Axes::add_patch(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{add_patch_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::cla(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{cla_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::contour(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{contour_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::fill(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{fill_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::fill_between( + const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{fill_between_attr(*args, **kwargs)}; +} + +std::tuple Axes::get_xlim() const +{ + const pybind11::list ret = get_xlim_attr(); + return {ret[0].cast(), ret[1].cast()}; +} + +std::tuple Axes::get_ylim() const +{ + const pybind11::list ret = get_ylim_attr(); + return {ret[0].cast(), ret[1].cast()}; +} + +PyObjectWrapper Axes::grid(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{grid_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::imshow(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{imshow_attr(*args, **kwargs)}; +} + +legend::Legend Axes::legend(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return legend::Legend{legend_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::plot(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{plot_attr(*args, **kwargs)}; +} + +quiver::Quiver Axes::quiver(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return Quiver{quiver_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_aspect(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_aspect_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_title(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_title_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_xlabel(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_xlabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_xlim(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_xlim_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_ylabel(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_ylabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_ylim(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_ylim_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::text(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{text_attr(*args, **kwargs)}; +} + +void Axes::load_attrs() +{ + LOAD_FUNC_ATTR(add_patch, self_); + LOAD_FUNC_ATTR(cla, self_); + LOAD_FUNC_ATTR(contour, self_); + LOAD_FUNC_ATTR(contourf, self_); + LOAD_FUNC_ATTR(fill, self_); + LOAD_FUNC_ATTR(fill_between, self_); + LOAD_FUNC_ATTR(get_xlim, self_); + LOAD_FUNC_ATTR(get_ylim, self_); + LOAD_FUNC_ATTR(grid, self_); + LOAD_FUNC_ATTR(imshow, self_); + LOAD_FUNC_ATTR(legend, self_); + LOAD_FUNC_ATTR(quiver, self_); + LOAD_FUNC_ATTR(plot, self_); + LOAD_FUNC_ATTR(scatter, self_); + LOAD_FUNC_ATTR(set_aspect, self_); + LOAD_FUNC_ATTR(set_title, self_); + LOAD_FUNC_ATTR(set_xlabel, self_); + LOAD_FUNC_ATTR(set_xlim, self_); + LOAD_FUNC_ATTR(set_ylabel, self_); + LOAD_FUNC_ATTR(set_ylim, self_); + LOAD_FUNC_ATTR(text, self_); +} +} // namespace axes +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/common.cpp b/common/autoware_pyplot/src/common.cpp new file mode 100644 index 0000000000000..5b3fffa37f30e --- /dev/null +++ b/common/autoware_pyplot/src/common.cpp @@ -0,0 +1,30 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace autoware::pyplot +{ +inline namespace common +{ +PyObjectWrapper::PyObjectWrapper(const pybind11::object & object) +{ + self_ = object; +} +PyObjectWrapper::PyObjectWrapper(pybind11::object && object) +{ + self_ = std::move(object); +} +} // namespace common +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/figure.cpp b/common/autoware_pyplot/src/figure.cpp new file mode 100644 index 0000000000000..07aacf8dd516a --- /dev/null +++ b/common/autoware_pyplot/src/figure.cpp @@ -0,0 +1,66 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace autoware::pyplot +{ +inline namespace figure +{ +Figure::Figure(const pybind11::object & object) : PyObjectWrapper(object) +{ + load_attrs(); +} +Figure::Figure(pybind11::object && object) : PyObjectWrapper(object) +{ + load_attrs(); +} + +void Figure::load_attrs() +{ + LOAD_FUNC_ATTR(add_axes, self_); + LOAD_FUNC_ATTR(add_subplot, self_); + LOAD_FUNC_ATTR(colorbar, self_); + LOAD_FUNC_ATTR(savefig, self_); + LOAD_FUNC_ATTR(tight_layout, self_); +} + +axes::Axes Figure::add_axes(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return axes::Axes{add_axes_attr(*args, **kwargs)}; +} + +axes::Axes Figure::add_subplot(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return axes::Axes{add_subplot_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::colorbar(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{colorbar_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::savefig(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{savefig_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::tight_layout( + const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{tight_layout_attr(*args, **kwargs)}; +} +} // namespace figure +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/legend.cpp b/common/autoware_pyplot/src/legend.cpp new file mode 100644 index 0000000000000..e5a128725fec7 --- /dev/null +++ b/common/autoware_pyplot/src/legend.cpp @@ -0,0 +1,28 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace autoware::pyplot +{ +inline namespace legend +{ +Legend::Legend(const pybind11::object & object) : PyObjectWrapper(object) +{ +} +Legend::Legend(pybind11::object && object) : PyObjectWrapper(object) +{ +} +} // namespace legend +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/patches.cpp b/common/autoware_pyplot/src/patches.cpp new file mode 100644 index 0000000000000..4df4de27e81e3 --- /dev/null +++ b/common/autoware_pyplot/src/patches.cpp @@ -0,0 +1,45 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace autoware::pyplot +{ +inline namespace patches +{ +Circle::Circle(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Circle")) +{ + self_ = self_(*args, **kwargs); +} + +Ellipse::Ellipse(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Ellipse")) +{ + self_ = self_(*args, **kwargs); +} + +Rectangle::Rectangle(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Rectangle")) +{ + self_ = self_(*args, **kwargs); +} + +Polygon::Polygon(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Polygon")) +{ + self_ = self_(*args, **kwargs); +} +} // namespace patches +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/pyplot.cpp b/common/autoware_pyplot/src/pyplot.cpp new file mode 100644 index 0000000000000..d45d34a35d767 --- /dev/null +++ b/common/autoware_pyplot/src/pyplot.cpp @@ -0,0 +1,205 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace autoware::pyplot +{ +PyPlot::PyPlot(const pybind11::module & mod_) : mod(mod_) +{ + load_attrs(); +} + +void PyPlot::load_attrs() +{ + LOAD_FUNC_ATTR(axes, mod); + LOAD_FUNC_ATTR(cla, mod); + LOAD_FUNC_ATTR(clf, mod); + LOAD_FUNC_ATTR(figure, mod); + LOAD_FUNC_ATTR(gca, mod); + LOAD_FUNC_ATTR(gcf, mod); + LOAD_FUNC_ATTR(gci, mod); + LOAD_FUNC_ATTR(grid, mod); + LOAD_FUNC_ATTR(imshow, mod); + LOAD_FUNC_ATTR(legend, mod); + LOAD_FUNC_ATTR(plot, mod); + LOAD_FUNC_ATTR(quiver, mod); + LOAD_FUNC_ATTR(savefig, mod); + LOAD_FUNC_ATTR(scatter, mod); + LOAD_FUNC_ATTR(show, mod); + LOAD_FUNC_ATTR(subplot, mod); + LOAD_FUNC_ATTR(subplots, mod); + LOAD_FUNC_ATTR(title, mod); + LOAD_FUNC_ATTR(xlabel, mod); + LOAD_FUNC_ATTR(xlim, mod); + LOAD_FUNC_ATTR(ylabel, mod); + LOAD_FUNC_ATTR(ylim, mod); +} + +axes::Axes PyPlot::axes(const pybind11::dict & kwargs) +{ + return axes::Axes{axes_attr(**kwargs)}; +} + +PyObjectWrapper PyPlot::cla(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{cla_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::clf(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{clf_attr(*args, **kwargs)}; +} + +figure::Figure PyPlot::figure(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return figure::Figure{figure_attr(*args, **kwargs)}; +} + +axes::Axes PyPlot::gca(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return axes::Axes{gca_attr(*args, **kwargs)}; +} + +figure::Figure PyPlot::gcf(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return figure::Figure{gcf_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::gci(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{gci_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::grid(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{grid_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::imshow(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{imshow_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::legend(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{legend_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::plot(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{plot_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::quiver(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{quiver_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::scatter(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{scatter_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::savefig(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{savefig_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::show(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{show_attr(*args, **kwargs)}; +} + +axes::Axes PyPlot::subplot(const pybind11::dict & kwargs) +{ + return axes::Axes(subplot_attr(**kwargs)); +} + +axes::Axes PyPlot::subplot(int cri) +{ + return axes::Axes(subplot_attr(cri)); +} + +std::tuple PyPlot::subplots(const pybind11::dict & kwargs) +{ + pybind11::list ret = subplots_attr(**kwargs); + pybind11::object fig = ret[0]; + pybind11::object ax = ret[1]; + return {figure::Figure(fig), axes::Axes(ax)}; +} + +std::tuple> PyPlot::subplots( + int r, int c, const pybind11::dict & kwargs) +{ + // subplots() returns [][] (if r > 1 && c > 1) else [] + // return []axes in row-major + // NOTE: equal to Axes.flat + pybind11::tuple args = pybind11::make_tuple(r, c); + pybind11::list ret = subplots_attr(*args, **kwargs); + std::vector axes; + pybind11::object fig = ret[0]; + figure::Figure figure(fig); + if (r == 1 && c == 1) { + // python returns Axes + axes.emplace_back(ret[1]); + } else if (r == 1 || c == 1) { + // python returns []Axes + pybind11::list axs = ret[1]; + for (int i = 0; i < r * c; ++i) axes.emplace_back(axs[i]); + } else { + // python returns [][]Axes + pybind11::list axs = ret[1]; + for (pybind11::size_t i = 0; i < axs.size(); ++i) { + pybind11::list ax_i = axs[i]; + for (unsigned j = 0; j < ax_i.size(); ++j) axes.emplace_back(ax_i[j]); + } + } + return {figure, axes}; +} + +PyObjectWrapper PyPlot::title(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{title_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::xlabel(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{xlabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::xlim(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{xlim_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::ylabel(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{ylabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::ylim(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{ylim_attr(*args, **kwargs)}; +} + +PyPlot import() +{ + auto mod = pybind11::module::import("matplotlib.pyplot"); + auto g_pyplot = PyPlot(mod); + return g_pyplot; +} + +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/quiver.cpp b/common/autoware_pyplot/src/quiver.cpp new file mode 100644 index 0000000000000..72614fb6227a7 --- /dev/null +++ b/common/autoware_pyplot/src/quiver.cpp @@ -0,0 +1,28 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace autoware::pyplot +{ +inline namespace quiver +{ +Quiver::Quiver(const pybind11::object & object) : PyObjectWrapper(object) +{ +} +Quiver::Quiver(pybind11::object && object) : PyObjectWrapper(object) +{ +} +} // namespace quiver +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/text.cpp b/common/autoware_pyplot/src/text.cpp new file mode 100644 index 0000000000000..024c7c2daf946 --- /dev/null +++ b/common/autoware_pyplot/src/text.cpp @@ -0,0 +1,35 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace autoware::pyplot +{ +inline namespace text +{ +Text::Text(const pybind11::object & object) : PyObjectWrapper(object) +{ +} + +Text::Text(pybind11::object && object) : PyObjectWrapper(object) +{ +} + +void Text::load_attrs() +{ + LOAD_FUNC_ATTR(set_rotation, self_); +} +} // namespace text +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/test/test_pyplot.cpp b/common/autoware_pyplot/test/test_pyplot.cpp new file mode 100644 index 0000000000000..2055709c61f52 --- /dev/null +++ b/common/autoware_pyplot/test/test_pyplot.cpp @@ -0,0 +1,64 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include +#include +/* + very weirdly, you must include to pass vector. Although the code + compiles without it, the executable crashes at runtime + */ +#include + +#include + +TEST(PyPlot, single_plot) +{ + // NOTE: somehow, running multiple tests simultaneously causes the python interpreter to crash + py::scoped_interpreter guard{}; + auto plt = autoware::pyplot::import(); + { + plt.plot(Args(std::vector({1, 3, 2, 4})), Kwargs("color"_a = "blue", "linewidth"_a = 1.0)); + plt.xlabel(Args("x-title")); + plt.ylabel(Args("y-title")); + plt.title(Args("title")); + plt.xlim(Args(0, 5)); + plt.ylim(Args(0, 5)); + plt.grid(Args(true)); + plt.savefig(Args("test_single_plot.png")); + } + { + auto [fig, axes] = plt.subplots(1, 2); + auto & ax1 = axes[0]; + auto & ax2 = axes[1]; + + auto c = + autoware::pyplot::Circle(Args(py::make_tuple(0, 0), 0.5), Kwargs("fc"_a = "g", "ec"_a = "r")); + ax1.add_patch(Args(c.unwrap())); + + auto e = autoware::pyplot::Ellipse( + Args(py::make_tuple(-0.25, 0), 0.5, 0.25), Kwargs("fc"_a = "b", "ec"_a = "y")); + ax1.add_patch(Args(e.unwrap())); + + auto r = autoware::pyplot::Rectangle( + Args(py::make_tuple(0, 0), 0.25, 0.5), Kwargs("ec"_a = "#000000", "fill"_a = false)); + ax2.add_patch(Args(r.unwrap())); + + ax1.set_aspect(Args("equal")); + ax2.set_aspect(Args("equal")); + plt.savefig(Args("test_double_plot.svg")); + } +} diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md index 42b3f4c9f96de..f0f4a6c9f7014 100644 --- a/control/autoware_autonomous_emergency_braking/README.md +++ b/control/autoware_autonomous_emergency_braking/README.md @@ -60,6 +60,8 @@ We do not activate AEB module if it satisfies the following conditions. ### 2. Generate a predicted path of the ego vehicle +#### IMU path generation + AEB generates a predicted footprint path based on current velocity and current angular velocity obtained from attached sensors. Note that if `use_imu_path` is `false`, it skips this step. This predicted path is generated as: $$ @@ -68,9 +70,21 @@ y_{k+1} = y_k + v sin(\theta_k) dt \\ \theta_{k+1} = \theta_k + \omega dt $$ -where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance. +where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance with the `imu_prediction_time_interval` parameter. The IMU path is generated considering a time horizon, defined by the `imu_prediction_time_horizon` parameter. + +Since the IMU path generation only uses the ego vehicle's current angular velocity, disregarding the MPC's planner steering, the shape of the IMU path tends to get distorted quite easily and protrude out of the ego vehicle's current lane, possibly causing unwanted emergency stops. That is why it is not recommended to use a big `imu_prediction_time_horizon`. To fix this issue, the IMU path's length can be cut short by tuning the `max_generated_imu_path_length` parameter, the IMU path generation will be cut short once its length surpasses this parameter's value. + +It is also possible to limit the IMU path length based on the predicted lateral deviation of the vehicle by setting the `limit_imu_path_lat_dev` parameter flag to "true", and setting a threshold lateral deviation with the `imu_path_lat_dev_threshold` parameter. That way, the AEB will generate a predicted IMU path until a given predicted ego pose surpasses the lateral deviation threshold, and the IMU path will be cut short when the ego vehicle is turning relatively fast. + +The advantage of setting a lateral deviation limit with the `limit_imu_path_lat_dev` parameter is that the `imu_prediction_time_horizon` and the `max_generated_imu_path_length` can be increased without worries about the IMU predicted path deforming beyond a certain threshold. The downside is that the IMU path will be cut short when the ego has a high angular velocity, in said cases, the AEB module would mostly rely on the MPC path to prevent or mitigate collisions. If it is assumed the ego vehicle will mostly travel along the centerline of its lanelets, it can be useful to set the lateral deviation threshold parameter `imu_path_lat_dev_threshold` to be equal to or smaller than the average lanelet width divided by 2, that way, the chance of the IMU predicted path leaving the current ego lanelet is smaller, and it is possible to increase the `imu_prediction_time_horizon` to prevent frontal collisions when the ego is mostly traveling in a straight line. + +The lateral deviation is measured using the ego vehicle's current position as a reference, and it measures the distance of the furthermost vertex of the predicted ego footprint to the predicted path. The following image illustrates how the lateral deviation of a given ego pose is measured. + +![measuring_lat_dev](./image/measuring-lat-dev-on-imu-path.drawio.svg) + +#### MPC path generation -On the other hand, if `use_predicted_trajectory` is set to true, the AEB module will use the predicted path from the MPC as a base to generate a footprint path. Both the IMU footprint path and the MPC footprint path can be used at the same time. +If the `use_predicted_trajectory` parameter is set to true, the AEB module will directly use the predicted path from the MPC as a base to generate a footprint path. It will copy the ego poses generated by the MPC until a given time horizon. The `mpc_prediction_time_horizon` parameter dictates how far ahead in the future the MPC path will predict the ego vehicle's movement. Both the IMU footprint path and the MPC footprint path can be used at the same time. ### 3. Get target obstacles @@ -82,7 +96,7 @@ The AEB module can filter the input pointcloud to find target obstacles with whi ##### Rough filtering -In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default is half of the ego vehicle width plus the `path_footprint_extra_margin` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The rough filtering step is illustrated below. +In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default is half of the ego vehicle width plus the `path_footprint_extra_margin` parameter plus the `expand_width` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The rough filtering step is illustrated below. ![rough_filtering](./image/obstacle_filtering_1.drawio.svg) @@ -94,26 +108,34 @@ Furthermore, a 2D convex hull is created around each detected cluster, the verti ##### Rigorous filtering -After Noise filtering, the module performs a geometric collision check to determine whether the filtered obstacles/hull vertices actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. Only the vertices with a possibility of collision are kept. +After Noise filtering, the module performs a geometric collision check to determine whether the filtered obstacles/hull vertices actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. Only the vertices with a possibility of collision are labeled as target obstacles. ![rigorous_filtering](./image/obstacle_filtering_2.drawio.svg) +##### Obstacle labeling + +After rigorous filtering, the remaining obstacles are labeled. An obstacle is given a "target" label for collision checking only if it falls within the ego vehicle's defined footprint (made using the ego vehicle's width and the `expand_width` parameter). For an emergency stop to occur, at least one obstacle needs to be labeled as a target. + +![labeling](./image/labeling.drawio.svg) + #### Using predicted objects to get target obstacles -If the `use_predicted_object_data` parameter is set to true, the AEB can use predicted object data coming from the perception modules, to get target obstacle points. This is done by obtaining the 2D intersection points between the ego's predicted footprint path and each of the predicted objects enveloping polygon or bounding box. +If the `use_predicted_object_data` parameter is set to true, the AEB can use predicted object data coming from the perception modules, to get target obstacle points. This is done by obtaining the 2D intersection points between the ego's predicted footprint path (made using the ego vehicle's width and the `expand_width` parameter) and each of the predicted objects enveloping polygon or bounding box. if there is no intersection, all points are discarded. ![predicted_object_and_path_intersection](./image/using-predicted-objects.drawio.svg) ### Finding the closest target obstacle -Once all target obstacles have been identified, the AEB module chooses the point that is closest to the ego vehicle as the candidate for collision checking. Only the closest point is considered because RSS distance is used to judge if a collision will happen or not, and if the closest vertex to the ego is deemed to be safe from collision, the rest of the target obstacles will also be safe. +After identifying all possible obstacles using pointcloud data and/or predicted object data, the AEB module selects the closest point to the ego vehicle as the candidate for collision checking. The "closest object" is defined as an obstacle within the ego vehicle's footprint, determined by its width and the `expand_width` parameter, that is closest to the ego vehicle along the longitudinal axis, using the IMU or MPC path as a reference. Target obstacles are prioritized over those outside the ego path, even if the latter are longitudinally closer. This prioritization ensures that the collision check focuses on objects that pose the highest risk based on the vehicle's trajectory. + +If no target obstacles are found, the AEB module considers other nearby obstacles outside the path. In such cases, it skips the collision check but records the position of the closest obstacle to calculate its speed (Step #4). Note that, obstacles obtained with predicted object data are all target obstacles since they are within the ego footprint path and it is not necessary to calculate their speed (it is already calculated by the perception module). Such obstacles are excluded from step #4. ![closest_object](./image/closest-point.drawio.svg) ### 4. Obstacle velocity estimation To begin calculating the target point's velocity, the point must enter the speed calculation area, -which is defined by the `speed_calculation_expansion_margin` parameter. +which is defined by the `speed_calculation_expansion_margin` parameter plus the ego vehicles width and the `expand_width` parameter. Depending on the operational environment, this margin can reduce unnecessary autonomous emergency braking caused by velocity miscalculations during the initial calculation steps. @@ -148,19 +170,24 @@ $$ where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector $$v_{pos} = o_{pos} - prev_{pos} $$ and $v_{ego}$ is the ego's current speed, which accounts for the movement of points caused by the ego moving and not the object. All these equations are performed disregarding the z axis (in 2D). -Note that, the object velocity is calculated against the ego's current movement direction. If the object moves in the opposite direction to the ego's movement, the object velocity will be negative, which will reduce the rss distance on the next step. +Note that the object velocity is calculated against the ego's current movement direction. If the object moves in the opposite direction to the ego's movement, the object velocity will be negative, which will reduce the rss distance on the next step. The resulting estimated object speed is added to a queue of speeds with timestamps. The AEB then checks for expiration of past speed estimations and eliminates expired speed measurements from the queue, the object expiration is determined by checking if the time elapsed since the speed was first added to the queue is larger than the parameter `previous_obstacle_keep_time`. Finally, the median speed of the queue is calculated. The median speed will be used to calculate the RSS distance used for collision checking. ### 5. Collision check with target obstacles using RSS distance -In the fourth step, it checks the collision with the closest obstacle point using RSS distance. RSS distance is formulated as: +In the fifth step, the AEB module checks for collision with the closest target obstacle using RSS distance. +Only the closest target object is evaluated because RSS distance is used to determine collision risk. If the nearest target point is deemed safe, all other potential obstacles within the path are also assumed to be safe. + +RSS distance is formulated as: $$ d = v_{ego}*t_{response} + v_{ego}^2/(2*a_{min}) -(sign(v_{obj})) * v_{obj}^2/(2*a_{obj_{min}}) + offset $$ -where $v_{ego}$ and $v_{obj}$ is current ego and obstacle velocity, $a_{min}$ and $a_{obj_{min}}$ is ego and object minimum acceleration (maximum deceleration), $t_{response}$ is response time of the ego vehicle to start deceleration. Therefore the distance from the ego vehicle to the obstacle is smaller than this RSS distance $d$, the ego vehicle send emergency stop signals. This is illustrated in the following picture. +where $v_{ego}$ and $v_{obj}$ is current ego and obstacle velocity, $a_{min}$ and $a_{obj_{min}}$ is ego and object minimum acceleration (maximum deceleration), $t_{response}$ is response time of the ego vehicle to start deceleration. Therefore the distance from the ego vehicle to the obstacle is smaller than this RSS distance $d$, the ego vehicle send emergency stop signals. + +Only obstacles classified as "targets" (as defined in Step #3) are considered for RSS distance calculations. Among these "target" obstacles, the one closest to the ego vehicle is used for the calculation. If no "target" obstacles are present—meaning no obstacles fall within the ego vehicle's predicted path (determined by its width and an expanded margin)—this step is skipped. Instead, the position of the closest obstacle is recorded for future speed calculations (Step #4). In this scenario, no emergency stop diagnostic message is generated. The process is illustrated in the accompanying diagram. ![rss_check](./image/rss_check.drawio.svg) @@ -215,7 +242,7 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t | maximum_cluster_size | [-] | int | maximum amount of points contained by a cluster for it to be considered as a possible target obstacle | 10000 | | min_generated_imu_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | | max_generated_imu_path_length | [m] | double | maximum distance for a predicted path generated by sensors | 10.0 | -| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | +| expand_width | [m] | double | expansion width of the ego vehicle for collision checking, path cropping and speed calculation | 0.1 | | longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | | t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | | a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | @@ -225,7 +252,8 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t | mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 | | mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 | | aeb_hz | [-] | double | frequency at which AEB operates per second | 10 | -| speed_calculation_expansion_margin | [m] | double | expansion width of the ego vehicle for the beginning speed calculation | 0.1 | +| speed_calculation_expansion_margin | [m] | double | expansion width of the ego vehicle footprint used when calculating the closest object's speed | 0.7 | +| path_footprint_extra_margin | [m] | double | this parameters expands the ego footprint used to crop the AEB input pointcloud | 1.0 | ## Limitations diff --git a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index f7548536beaef..99ca4d4ef52cb 100644 --- a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -3,10 +3,12 @@ # Ego path calculation use_predicted_trajectory: true use_imu_path: true + limit_imu_path_lat_dev: false use_pointcloud_data: true use_predicted_object_data: false use_object_velocity_calculation: true check_autoware_state: true + imu_path_lat_dev_threshold: 1.75 min_generated_imu_path_length: 0.5 max_generated_imu_path_length: 10.0 imu_prediction_time_horizon: 1.5 @@ -21,14 +23,14 @@ # Point cloud partitioning detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 - voxel_grid_x: 0.05 - voxel_grid_y: 0.05 - voxel_grid_z: 100000.0 + voxel_grid_x: 0.1 + voxel_grid_y: 0.1 + voxel_grid_z: 0.5 # Point cloud cropping - expand_width: 0.1 - path_footprint_extra_margin: 4.0 - speed_calculation_expansion_margin: 0.5 + expand_width: -0.2 + path_footprint_extra_margin: 1.0 + speed_calculation_expansion_margin: 0.7 # Point cloud clustering cluster_tolerance: 0.15 #[m] @@ -37,10 +39,10 @@ maximum_cluster_size: 10000 # RSS distance collision check - longitudinal_offset: 2.0 + longitudinal_offset: 1.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - collision_keeping_sec: 2.0 + collision_keeping_sec: 3.0 previous_obstacle_keep_time: 1.0 aeb_hz: 10.0 diff --git a/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg b/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg new file mode 100644 index 0000000000000..0f9995a9918cd --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg @@ -0,0 +1,390 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Labeling target obstacles +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ expand_width + speed_calculation_expansion_margin + ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + +
+
+
+ Target obstacles +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ expand_width  + ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + +
+
+
+
Regular obstacles (used only for speed calculation)
+
+
+
+
+ +
+
+
+
+ + + + + +
+
+
+
diff --git a/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg b/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg new file mode 100644 index 0000000000000..9dbd85f28207e --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg @@ -0,0 +1,374 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Y +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat dev +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat threshold +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ X +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat dev +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ IMU path is cut the before lateral deviation threshold is exceeded +
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg index ee5ec62fbc1d4..48f7659c36d8d 100644 --- a/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg @@ -5,296 +5,436 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="595px" - height="534px" - viewBox="-0.5 -0.5 595 534" - content="<mxfile host="app.diagrams.net" modified="2024-06-13T07:18:04.299Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/121.0.0.0 Safari/537.36" etag="hdT1j-Hjagtqen0Xp5w0" version="24.5.4" type="google" scale="1" border="0"> <diagram name="Page-1" id="eIJewT680QnBEBDdotri"> <mxGraphModel dx="1364" dy="940" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="8Dxr__kcSdhv2497bxnN-1" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="50" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-2" value="" style="group;opacity=30;" vertex="1" connectable="0" parent="1"> <mxGeometry x="340" y="325" width="420" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-3" value="" style="group;fillColor=#dae8fc;strokeColor=#6c8ebf;container=0;" vertex="1" connectable="0" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry width="420" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-4" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry x="280" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-5" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry x="140" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-6" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-7" value="" style="group" vertex="1" connectable="0" parent="1"> <mxGeometry x="340" y="370" width="420" height="85" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-8" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry x="280" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-9" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry x="140" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-10" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-11" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="350.0000000000002" y="109.48676906857327" as="sourcePoint" /> <mxPoint x="456.7649999999999" y="109.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-12" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="87" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-13" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="103" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-14" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="117" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-15" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="87" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-16" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="125" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-17" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="97" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-18" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="341" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-19" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="456.7649999999999" y="400.5" as="targetPoint" /> <mxPoint x="350.0000000000002" y="400.48676906857327" as="sourcePoint" /> </mxGeometry> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-20" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,PD94bWwgdmVyc2lvbj0iMS4wIiBlbmNvZGluZz0iVVRGLTgiIHN0YW5kYWxvbmU9Im5vIj8+CjwhLS0gQ3JlYXRlZCB3aXRoIElua3NjYXBlIChodHRwOi8vd3d3Lmlua3NjYXBlLm9yZy8pIC0tPgoKPHN2ZwogICB3aWR0aD0iNy4zMDU0NjA5bW0iCiAgIGhlaWdodD0iMy4xODI4MzIybW0iCiAgIHZpZXdCb3g9IjAgMCA3LjMwNTQ2MDkgMy4xODI4MzIyIgogICB2ZXJzaW9uPSIxLjEiCiAgIGlkPSJzdmcxIgogICB4bWw6c3BhY2U9InByZXNlcnZlIgogICBpbmtzY2FwZTp2ZXJzaW9uPSIxLjMgKDE6MS4zKzIwMjMwNzIzMTQ1OSswZTE1MGVkNmM0KSIKICAgc29kaXBvZGk6ZG9jbmFtZT0iYmVoYXZpb3JfcGF0aF9wbGFubmVyLnN2ZyIKICAgeG1sbnM6aW5rc2NhcGU9Imh0dHA6Ly93d3cuaW5rc2NhcGUub3JnL25hbWVzcGFjZXMvaW5rc2NhcGUiCiAgIHhtbG5zOnNvZGlwb2RpPSJodHRwOi8vc29kaXBvZGkuc291cmNlZm9yZ2UubmV0L0RURC9zb2RpcG9kaS0wLmR0ZCIKICAgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIgogICB4bWxuczpzdmc9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIj48c29kaXBvZGk6bmFtZWR2aWV3CiAgICAgaWQ9Im5hbWVkdmlldzEiCiAgICAgcGFnZWNvbG9yPSIjZmZmZmZmIgogICAgIGJvcmRlcmNvbG9yPSIjMDAwMDAwIgogICAgIGJvcmRlcm9wYWNpdHk9IjAuMjUiCiAgICAgaW5rc2NhcGU6c2hvd3BhZ2VzaGFkb3c9IjIiCiAgICAgaW5rc2NhcGU6cGFnZW9wYWNpdHk9IjAuMCIKICAgICBpbmtzY2FwZTpwYWdlY2hlY2tlcmJvYXJkPSIwIgogICAgIGlua3NjYXBlOmRlc2tjb2xvcj0iI2QxZDFkMSIKICAgICBpbmtzY2FwZTpkb2N1bWVudC11bml0cz0ibW0iCiAgICAgaW5rc2NhcGU6em9vbT0iMTkuMTA5NTAxIgogICAgIGlua3NjYXBlOmN4PSIxNzkuODMyMDEiCiAgICAgaW5rc2NhcGU6Y3k9IjQ4MC40NDE2MyIKICAgICBpbmtzY2FwZTp3aW5kb3ctd2lkdGg9IjM3NzAiCiAgICAgaW5rc2NhcGU6d2luZG93LWhlaWdodD0iMjA5NiIKICAgICBpbmtzY2FwZTp3aW5kb3cteD0iNzAiCiAgICAgaW5rc2NhcGU6d2luZG93LXk9IjI3IgogICAgIGlua3NjYXBlOndpbmRvdy1tYXhpbWl6ZWQ9IjEiCiAgICAgaW5rc2NhcGU6Y3VycmVudC1sYXllcj0ibGF5ZXIxIiAvPjxkZWZzCiAgICAgaWQ9ImRlZnMxIiAvPjxnCiAgICAgaW5rc2NhcGU6bGFiZWw9IkxheWVyIDEiCiAgICAgaW5rc2NhcGU6Z3JvdXBtb2RlPSJsYXllciIKICAgICBpZD0ibGF5ZXIxIgogICAgIHRyYW5zZm9ybT0idHJhbnNsYXRlKC01MS4zMjMzMjMsLTEzMi4wNTM0MikiPjxyZWN0CiAgICAgICBzdHlsZT0iZmlsbDojZjhjZWNjO2ZpbGwtb3BhY2l0eToxO3N0cm9rZTojMDAwMDAwO3N0cm9rZS13aWR0aDowLjE1O3N0cm9rZS1kYXNoYXJyYXk6bm9uZSIKICAgICAgIGlkPSJyZWN0MSIKICAgICAgIHdpZHRoPSI3LjE1NTQ2MzciCiAgICAgICBoZWlnaHQ9IjMuMDMyODMxNCIKICAgICAgIHg9IjUxLjM5ODMyMyIKICAgICAgIHk9IjEzMi4xMjg0MiIKICAgICAgIHJ5PSIwLjkzNTU2ODM5IiAvPjxwYXRoCiAgICAgICBpZD0icGF0aDkiCiAgICAgICBzdHlsZT0iZmlsbDojZjhjZWNjO2ZpbGwtb3BhY2l0eToxO3N0cm9rZTojMDAwMDAwO3N0cm9rZS13aWR0aDowLjE1O3N0cm9rZS1kYXNoYXJyYXk6bm9uZSIKICAgICAgIGQ9Im0gNTYuNjM1MjgyLDEzNC43OTk4NCAtMS4xNDEzNjUsLTAuMjQ1NSBtIDEuMTQxMzY1LC0yLjA1ODEgLTEuMTQxMzY1LDAuMjQ1NSBtIC0yLjYzNzE1NiwyLjA4NDY3IDEuMjM4Mzg3LC0wLjI5ODYzIG0gLTEuMjM4Mzg3LC0yLjA1ODExIDEuMjM4Mzg3LDAuMjk4NjQgbSAwLjczOTM5MSwxLjc3MDY4IHYgMC4zNTcyNyBtIDAsLTIuNDkzOTYgdiAwLjM1NzI3IG0gLTAuNzgyMjUxLC0wLjAxNDEgaCAxLjQ1ODQwMSB2IDEuODA3ODkgaCAtMS40NTg0MDEgeiBtIC0wLjg0MDE1NCwtMC4zMzA4MyBoIDIuOTE2Mzk4IGMgMC41ODkwMTksMCAxLjA2MzIxMiwwLjMzOTM5IDEuMDYzMjEyLDAuNzYwOTYgdiAwLjk0NDg4IGMgMCwwLjQyMTU3IC0wLjQ3NDE5MywwLjc2MDk2IC0xLjA2MzIxMiwwLjc2MDk2IGggLTIuOTE2Mzk4IGMgLTAuNTg5MDE5LDAgLTEuMDYzMjEyLC0wLjMzOTM5IC0xLjA2MzIxMiwtMC43NjA5NiB2IC0wLjk0NDg4IGMgMCwtMC40MjE1NyAwLjQ3NDE5MywtMC43NjA5NiAxLjA2MzIxMiwtMC43NjA5NiB6IiAvPjwvZz48L3N2Zz4K;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="378" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-21" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="394" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-22" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="408" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-23" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="378" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-24" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="416" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-25" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="388" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-26" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,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;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="227.47000000000003" y="80.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-27" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,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;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="235.47000000000003" y="374.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-28" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="388.66999999999996" y="515" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-29" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;imageBorder=none;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="223" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-30" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="217" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-31" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="401.66999999999996" y="227" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-32" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="259" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-33" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="243" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-34" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="402.66999999999996" y="267" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-35" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-36" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="127" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-37" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478" y="115" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-38" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-39" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="418" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-40" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="479" y="406" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-41" value="Original Point Cloud" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="395" y="27" width="180" height="40" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-42" value="Cropping the Point Cloud with extended path" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="288.84" y="285" width="380" height="40" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-43" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="533" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-44" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="535" y="105" width="8" height="8" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + width="599px" + height="538px" + viewBox="-0.5 -0.5 599 538" + content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/131.0.0.0 Safari/537.36" version="24.8.8" scale="1" border="2"> <diagram name="Page-1" id="RP9hk2Fyg7B3xuBx3AVI"> <mxGraphModel dx="1314" dy="738" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="50" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="3" value="" style="group;opacity=30;" connectable="0" vertex="1" parent="1"> <mxGeometry x="340" y="325" width="420" height="155" as="geometry" /> </mxCell> <mxCell id="4" value="" style="group;fillColor=#dae8fc;strokeColor=#6c8ebf;container=0;" connectable="0" vertex="1" parent="3"> <mxGeometry width="420" height="155" as="geometry" /> </mxCell> <mxCell id="5" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry x="280" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="6" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry x="140" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="7" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8" value="" style="group" connectable="0" vertex="1" parent="1"> <mxGeometry x="340" y="370" width="420" height="85" as="geometry" /> </mxCell> <mxCell id="9" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry x="280" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="10" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry x="140" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="11" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry width="140" height="60" as="geometry" /> </mxCell> <mxCell id="12" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="350.0000000000002" y="109.48676906857327" as="sourcePoint" /> <mxPoint x="456.7649999999999" y="109.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="13" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="87" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="14" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="103" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="15" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="117" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="16" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="87" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="17" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="125" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="18" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="97" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="19" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="341" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="20" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="456.7649999999999" y="400.5" as="targetPoint" /> <mxPoint x="350.0000000000002" y="400.48676906857327" as="sourcePoint" /> </mxGeometry> </mxCell> <mxCell id="21" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="378" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="22" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="394" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="23" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="408" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="24" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="378" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="25" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="416" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="26" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="388" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="27" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,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;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="227.47000000000003" y="80.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="28" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,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;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="235.47000000000003" y="374.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="29" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="388.66999999999996" y="515" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="30" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;imageBorder=none;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="223" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="31" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="217" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="32" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="401.66999999999996" y="227" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="33" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="259" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="34" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="243" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="35" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="402.66999999999996" y="267" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="36" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="37" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="127" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="38" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478" y="115" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="39" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="40" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="418" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="41" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="479" y="406" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="42" value="Original Point Cloud" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="395" y="27" width="180" height="40" as="geometry" /> </mxCell> <mxCell id="43" value="Cropping the Point Cloud with extended path" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="288.84" y="285" width="380" height="40" as="geometry" /> </mxCell> <mxCell id="44" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="533" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="45" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="535" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="46" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;exitX=0.319;exitY=0.695;exitDx=0;exitDy=0;exitPerimeter=0;dashed=1;" edge="1" source="19" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="370" y="442" as="sourcePoint" /> <mxPoint x="370" y="402" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="47" value="expand_width +&amp;nbsp;path_footprint_extra_margin + Ego width / 2" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="46"> <mxGeometry x="-0.2514" y="1" relative="1" as="geometry"> <mxPoint x="164" y="49" as="offset" /> </mxGeometry> </mxCell> <mxCell id="48" value="" style="endArrow=classic;html=1;rounded=0;entryX=0.84;entryY=0.195;entryDx=0;entryDy=0;entryPerimeter=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="370.77" y="446" as="sourcePoint" /> <mxPoint x="420.56999999999994" y="496" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " style="background-color: rgb(255, 255, 255);" > - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
Original Point Cloud
-
-
-
- -
-
-
- - - - - - - -
-
-
- Cropping the Point Cloud with extended path -
-
-
-
- -
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Original Point Cloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Cropping the Point Cloud with extended path +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ expand_width + path_footprint_extra_margin + Ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + +
- - - - - -
diff --git a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg index 1d3dd824df5f0..82590ed107558 100644 --- a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg @@ -1,73 +1,170 @@ + + + - - - - - - - - - - - - - - - - -
-
- - Closest point distance -
-
-
-
-
-
- - - - - - -
-
- RSS distance -
-
-
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Closest point distance +
+
+
+
+
+
+ Closest point distance +
+
+
+
+
+ + + + + + + + + + + +
+
+
+ RSS distance +
+
+
+
+ RSS distance +
+
+
+
+
+ + + + + + + + + + +
+
+
+ ego vehicle width + 2 * expand_width +
+
+
+
+ ego vehicle width + 2 * expand_width +
+
+
+
+
+
+ + + + Text is not SVG - cannot display + +
diff --git a/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg b/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg index 37728253370e4..8df567f05962c 100644 --- a/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg @@ -3,19 +3,15 @@ - - - + @@ -24,24 +20,24 @@ - +
-
-
+
+
speed_calculation_expansion_margin
@@ -51,19 +47,19 @@ + >#svg-image-FwhNqmDYWad8ta0ORfnb .cls-1 { clip-path: url("#clippath"); } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-2 { fill: none; } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-2, #svg-image-FwhNqmDYWad8ta0ORfnb .cls-3 { stroke-width: 0px; } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-3 { fill: rgb(35, 31, 32); } @@ -87,147 +83,181 @@ - + - + - + - + - + - - + + - +
-
-
- speed_calculation_expansion_margin +
+
+ ego width / 2 + expand_width + speed_calculation_expansion_margin
- - - - - - - - - - - - - - - - - - - - - + + - +
-
-
- Closest Point +
+
+ Closest Point to ego
+ + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp index d18185c77335c..96efb5dc9ff1f 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp @@ -553,13 +553,14 @@ class AEB : public rclcpp::Node // Member variables bool publish_debug_pointcloud_; bool publish_debug_markers_; - bool publish_debug_time_; bool use_predicted_trajectory_; bool use_imu_path_; + bool limit_imu_path_lat_dev_; bool use_pointcloud_data_; bool use_predicted_object_data_; bool use_object_velocity_calculation_; bool check_autoware_state_; + double imu_path_lat_dev_threshold_; double path_footprint_extra_margin_; double speed_calculation_expansion_margin_; double detection_range_min_height_; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 846a7654d7313..7c4cf58cbc6e7 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -154,11 +155,13 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) publish_debug_markers_ = declare_parameter("publish_debug_markers"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + limit_imu_path_lat_dev_ = declare_parameter("limit_imu_path_lat_dev"); use_pointcloud_data_ = declare_parameter("use_pointcloud_data"); use_predicted_object_data_ = declare_parameter("use_predicted_object_data"); use_object_velocity_calculation_ = declare_parameter("use_object_velocity_calculation"); check_autoware_state_ = declare_parameter("check_autoware_state"); path_footprint_extra_margin_ = declare_parameter("path_footprint_extra_margin"); + imu_path_lat_dev_threshold_ = declare_parameter("imu_path_lat_dev_threshold"); speed_calculation_expansion_margin_ = declare_parameter("speed_calculation_expansion_margin"); detection_range_min_height_ = declare_parameter("detection_range_min_height"); @@ -216,12 +219,14 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter( updateParam(parameters, "publish_debug_markers", publish_debug_markers_); updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); updateParam(parameters, "use_imu_path", use_imu_path_); + updateParam(parameters, "limit_imu_path_lat_dev", limit_imu_path_lat_dev_); updateParam(parameters, "use_pointcloud_data", use_pointcloud_data_); updateParam(parameters, "use_predicted_object_data", use_predicted_object_data_); updateParam( parameters, "use_object_velocity_calculation", use_object_velocity_calculation_); updateParam(parameters, "check_autoware_state", check_autoware_state_); updateParam(parameters, "path_footprint_extra_margin", path_footprint_extra_margin_); + updateParam(parameters, "imu_path_lat_dev_threshold", imu_path_lat_dev_threshold_); updateParam( parameters, "speed_calculation_expansion_margin", speed_calculation_expansion_margin_); updateParam(parameters, "detection_range_min_height", detection_range_min_height_); @@ -647,14 +652,6 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object Path AEB::generateEgoPath(const double curr_v, const double curr_w) { autoware::universe_utils::ScopedTimeTrack st(std::string(__func__) + "(IMU)", *time_keeper_); - Path path; - double curr_x = 0.0; - double curr_y = 0.0; - double curr_yaw = 0.0; - geometry_msgs::msg::Pose ini_pose; - ini_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); - ini_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); - path.push_back(ini_pose); const double & dt = imu_prediction_time_interval_; const double distance_between_points = std::abs(curr_v) * dt; constexpr double minimum_distance_between_points{1e-2}; @@ -662,28 +659,57 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) // if distance between points is too small, arc length calculation is unreliable, so we skip // creating the path if (std::abs(curr_v) < 0.1 || distance_between_points < minimum_distance_between_points) { - return path; + return {}; } - const double & horizon = imu_prediction_time_horizon_; + // The initial pose is always aligned with the local reference frame. + geometry_msgs::msg::Pose initial_pose; + initial_pose.position = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + initial_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(0.0); + + const double horizon = imu_prediction_time_horizon_; + const double base_link_to_front_offset = vehicle_info_.max_longitudinal_offset_m; + const double rear_overhang = vehicle_info_.rear_overhang_m; + const double vehicle_half_width = expand_width_ + vehicle_info_.vehicle_width_m / 2.0; + + // Choose the coordinates of the ego footprint vertex that will used to check for lateral + // deviation + const auto longitudinal_offset = (curr_v > 0.0) ? base_link_to_front_offset : -rear_overhang; + const auto lateral_offset = (curr_v * curr_w > 0.0) ? vehicle_half_width : -vehicle_half_width; + + Path path{initial_pose}; + path.reserve(static_cast(horizon / dt)); + double curr_x = 0.0; + double curr_y = 0.0; + double curr_yaw = 0.0; double path_arc_length = 0.0; double t = 0.0; - bool finished_creating_path = false; - while (!finished_creating_path) { + while (true) { curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; curr_yaw = curr_yaw + curr_w * dt; - geometry_msgs::msg::Pose current_pose; - current_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); - current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); + geometry_msgs::msg::Pose current_pose = + autoware::universe_utils::calcOffsetPose(initial_pose, curr_x, curr_y, 0.0, curr_yaw); t += dt; path_arc_length += distance_between_points; + const auto edge_of_ego_vehicle = autoware::universe_utils::calcOffsetPose( + current_pose, longitudinal_offset, lateral_offset, 0.0) + .position; + + const bool basic_path_conditions_satisfied = + (t > horizon) && (path_arc_length > min_generated_imu_path_length_); + const bool path_length_threshold_surpassed = path_arc_length > max_generated_imu_path_length_; + const bool lat_dev_threshold_surpassed = + limit_imu_path_lat_dev_ && std::abs(edge_of_ego_vehicle.y) > imu_path_lat_dev_threshold_; + + if ( + basic_path_conditions_satisfied || path_length_threshold_surpassed || + lat_dev_threshold_surpassed) { + break; + } - finished_creating_path = (t > horizon) && (path_arc_length > min_generated_imu_path_length_); - finished_creating_path = - (finished_creating_path) || (path_arc_length > max_generated_imu_path_length_); path.push_back(current_pose); } return path; @@ -826,6 +852,7 @@ void AEB::createObjectDataUsingPredictedObjects( obj.position = obj_position; obj.velocity = obj_tangent_velocity; obj.distance_to_object = std::abs(dist_ego_to_object); + obj.is_target = true; object_data_vector.push_back(obj); collision_points_added = true; } diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index c2a58941cc144..3c00a4e6b5caf 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -210,7 +210,7 @@ TEST_F(TestAEB, checkEmptyPathAtZeroSpeed) const double velocity = 0.0; constexpr double yaw_rate = 0.0; const auto imu_path = aeb_node_->generateEgoPath(velocity, yaw_rate); - ASSERT_EQ(imu_path.size(), 1); + ASSERT_EQ(imu_path.size(), 0); } TEST_F(TestAEB, checkParamUpdate) diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h index 0e43b0b35aecd..35451ede3a6aa 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h @@ -171,12 +171,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid return *this; } - /** \brief Get the voxel covariance. - * \return covariance matrix - */ - const Eigen::Matrix3d & getCov() const { return (cov_); } - Eigen::Matrix3d & getCov() { return (cov_); } - /** \brief Get the inverse of the voxel covariance. * \return inverse covariance matrix */ @@ -191,11 +185,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid Eigen::Vector3d & getMean() { return (mean_); } - /** \brief Get the number of points contained by this voxel. - * \return number of points - */ - int getPointCount() const { return (nr_points_); } - /** \brief Number of points contained by voxel */ int nr_points_; @@ -352,6 +341,7 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid } // A wrapper of the real apply_filter + // cppcheck-suppress unusedFunction inline bool apply_filter_thread(int tid, GridNodeType & node) { apply_filter(processing_inputs_[tid], node); diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h index b173d164de97d..00c567775a6bf 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h @@ -132,15 +132,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration calculateNearestVoxelScoreEachPoint( const PointCloudSource & cloud) const; - inline void setRegularizationScaleFactor(float regularization_scale_factor) - { - params_.regularization_scale_factor = regularization_scale_factor; - } - inline void setRegularizationPose(Eigen::Matrix4f regularization_pose) { regularization_pose_ = regularization_pose; @@ -298,29 +247,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration GeometricPullOver::plan( if (road_lanes.empty() || pull_over_lanes.empty()) { return {}; } - const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes); const auto & p = parallel_parking_parameters_; const double max_steer_angle = @@ -69,10 +68,12 @@ std::optional GeometricPullOver::plan( return {}; } + const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *planner_data->route_handler, left_side_parking_); const auto arc_path = planner_.getArcPath(); // check lane departure with road and shoulder lanes - if (lane_departure_checker_.checkPathWillLeaveLane(lanes, arc_path)) return {}; + if (lane_departure_checker_.checkPathWillLeaveLane({departure_check_lane}, arc_path)) return {}; auto pull_over_path_opt = PullOverPath::create( getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index e1184c49e40ba..da99c830c68bb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -292,18 +292,12 @@ std::optional ShiftPullOver::generatePullOverPath( return is_footprint_in_any_polygon(footprint); }); }); - const bool is_in_lanes = std::invoke([&]() -> bool { - const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); - const auto & dp = planner_data->drivable_area_expansion_parameters; - const auto expanded_lanes = utils::expandLanelets( - drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - const auto combined_drivable = utils::combineDrivableLanes( - expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes); - return !lane_departure_checker_.checkPathWillLeaveLane( - utils::transformToLanelets(combined_drivable), pull_over_path.parking_path()); - }); + + const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *planner_data->route_handler, left_side_parking_); + const bool is_in_lanes = !lane_departure_checker_.checkPathWillLeaveLane( + {departure_check_lane}, pull_over_path.parking_path()); + if (!is_in_parking_lots && !is_in_lanes) { return {}; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index 5b925bd5ffd8e..bd32cf42293a7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -26,6 +26,7 @@ Takamasa Horibe Zulfaqar Azmi Go Sakayori + Alqudah Mohammad Apache License 2.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index f0fc87648bc4a..f7fc4ee48d364 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -780,8 +780,6 @@ void StaticObstacleAvoidanceModule::updateEgoBehavior( insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); - setStopReason(StopReason::AVOIDANCE, path.path); - setVelocityFactor(path.path); }