diff --git a/common/autoware_pyplot/CMakeLists.txt b/common/autoware_pyplot/CMakeLists.txt index 6922d5d9306f7..5871929676a2d 100644 --- a/common/autoware_pyplot/CMakeLists.txt +++ b/common/autoware_pyplot/CMakeLists.txt @@ -15,8 +15,12 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} STATIC DIRECTORY src ) +target_compile_options(${PROJECT_NAME} PUBLIC "-fPIC") target_link_libraries(${PROJECT_NAME} ${Python3_LIBRARIES} pybind11::embed) +# NOTE(soblin): this is workaround for propagating the include of "Python.h" to user modules to avoid "'Python.h' not found" +ament_export_include_directories(${Python3_INCLUDE_DIRS}) + if(BUILD_TESTING) find_package(ament_cmake_ros REQUIRED) diff --git a/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp new file mode 100644 index 0000000000000..c2185e65422e8 --- /dev/null +++ b/common/autoware_test_utils/include/autoware_test_utils/visualization.hpp @@ -0,0 +1,229 @@ +// Copyright 2024 TIER IV +// +// 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. + +// NOTE(soblin): this file is intentionally inline to deal with link issue + +#ifndef AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ +#define AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::test_utils +{ + +struct PointConfig +{ + std::optional color{}; + std::optional marker{}; + std::optional marker_size{}; +}; + +struct LineConfig +{ + static constexpr const char * default_color = "blue"; + static LineConfig defaults() + { + return LineConfig{std::string(default_color), 1.0, "solid", std::nullopt}; + } + std::optional color{}; + std::optional linewidth{}; + std::optional linestyle{}; + std::optional label{}; +}; + +struct LaneConfig +{ + static LaneConfig defaults() { return LaneConfig{std::nullopt, LineConfig::defaults(), true}; } + + std::optional label{}; + std::optional line_config{}; + bool plot_centerline = true; // alpha{}; + std::optional color{}; + bool fill{true}; + std::optional linewidth{}; + std::optional point_config{}; +}; + +/** + * @brief plot the linestring by `axes.plot()` + * @param [in] config_opt argument for plotting the linestring. if valid, each field is used as the + * kwargs + */ +inline void plot_lanelet2_object( + const lanelet::ConstLineString3d & line, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + py::dict kwargs{}; + if (config_opt) { + const auto & config = config_opt.value(); + if (config.color) { + kwargs["color"] = config.color.value(); + } + if (config.linewidth) { + kwargs["linewidth"] = config.linewidth.value(); + } + if (config.linestyle) { + kwargs["linestyle"] = config.linestyle.value(); + } + if (config.label) { + kwargs["label"] = config.label.value(); + } + } + std::vector xs; + for (const auto & p : line) { + xs.emplace_back(p.x()); + } + std::vector ys; + for (const auto & p : line) { + ys.emplace_back(p.y()); + } + axes.plot(Args(xs, ys), kwargs); +} + +/** + * @brief plot the left/right bounds and optionally centerline + * @param [in] args used for plotting the left/right bounds as + */ +inline void plot_lanelet2_object( + const lanelet::ConstLanelet & lanelet, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + const auto left = lanelet.leftBound(); + const auto right = lanelet.rightBound(); + + const auto line_config = [&]() -> std::optional { + if (!config_opt) { + return LineConfig{std::string(LineConfig::default_color)}; + } + return config_opt.value().line_config; + }(); + + if (config_opt) { + const auto & config = config_opt.value(); + + // plot lanelet centerline + if (config.plot_centerline) { + auto centerline_config = [&]() -> LineConfig { + if (!config.line_config) { + return LineConfig{"k", std::nullopt, "dashed"}; + } + auto cfg = config.line_config.value(); + cfg.color = "k"; + cfg.linestyle = "dashed"; + return cfg; + }(); + plot_lanelet2_object( + lanelet.centerline(), axes, std::make_optional(std::move(centerline_config))); + } + + // plot lanelet-id + const auto center = (left.front().basicPoint2d() + left.back().basicPoint2d() + + right.front().basicPoint2d() + right.back().basicPoint2d()) / + 4.0; + axes.text(Args(center.x(), center.y(), std::to_string(lanelet.id()))); + } + + if (config_opt && config_opt.value().label) { + auto left_line_config_for_legend = line_config ? line_config.value() : LineConfig::defaults(); + left_line_config_for_legend.label = config_opt.value().label.value(); + + // plot left + plot_lanelet2_object(lanelet.leftBound(), axes, left_line_config_for_legend); + + // plot right + plot_lanelet2_object(lanelet.rightBound(), axes, line_config); + } else { + // plot left + plot_lanelet2_object(lanelet.leftBound(), axes, line_config); + + // plot right + plot_lanelet2_object(lanelet.rightBound(), axes, line_config); + } + + // plot centerline direction + const auto centerline_size = lanelet.centerline().size(); + const auto mid_index = centerline_size / 2; + const auto before = static_cast(std::max(0, mid_index - 1)); + const auto after = static_cast(std::min(centerline_size - 1, mid_index + 1)); + const auto p_before = lanelet.centerline()[before]; + const auto p_after = lanelet.centerline()[after]; + const double azimuth = std::atan2(p_after.y() - p_before.y(), p_after.x() - p_before.x()); + const auto & mid = lanelet.centerline()[mid_index]; + axes.quiver( + Args(mid.x(), mid.y(), std::cos(azimuth), std::sin(azimuth)), Kwargs("units"_a = "width")); +} + +/** + * @brief plot the polygon as matplotlib.patches.Polygon + * @param [in] config_opt argument for plotting the polygon. if valid, each field is used as the + * kwargs + */ +inline void plot_lanelet2_object( + const lanelet::ConstPolygon3d & polygon, autoware::pyplot::Axes & axes, + const std::optional & config_opt = std::nullopt) +{ + std::vector> xy(polygon.size()); + for (unsigned i = 0; i < polygon.size(); ++i) { + xy.at(i) = std::vector({polygon[i].x(), polygon[i].y()}); + } + py::dict kwargs; + if (config_opt) { + const auto & config = config_opt.value(); + if (config.alpha) { + kwargs["alpha"] = config.alpha.value(); + } + if (config.color) { + kwargs["color"] = config.color.value(); + } + kwargs["fill"] = config.fill; + if (config.linewidth) { + kwargs["linewidth"] = config.linewidth.value(); + } + } + auto poly = autoware::pyplot::Polygon(Args(xy), kwargs); + axes.add_patch(Args(poly.unwrap())); +} + +/** + * @brief plot the point by `axes.plot()` + * @param [in] config_opt argument for plotting the point. if valid, each field is used as the + * kwargs + */ +/* +void plot_lanelet2_point( +const lanelet::ConstPoint3d & point, autoware::pyplot::Axes & axes, +const std::optional & config_opt = std::nullopt); +*/ +} // namespace autoware::test_utils + +#endif // AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_ diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 22572abb72b69..c328f37ba357d 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -23,6 +23,7 @@ autoware_map_msgs autoware_perception_msgs autoware_planning_msgs + autoware_pyplot autoware_universe_utils autoware_vehicle_msgs lanelet2_io