Skip to content

Commit b9ebc42

Browse files
authored
feat(autoware_test_utils): add visualization (#9603)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent d99caf9 commit b9ebc42

File tree

3 files changed

+234
-0
lines changed

3 files changed

+234
-0
lines changed

common/autoware_pyplot/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,12 @@ autoware_package()
1515
ament_auto_add_library(${PROJECT_NAME} STATIC
1616
DIRECTORY src
1717
)
18+
target_compile_options(${PROJECT_NAME} PUBLIC "-fPIC")
1819
target_link_libraries(${PROJECT_NAME} ${Python3_LIBRARIES} pybind11::embed)
1920

21+
# NOTE(soblin): this is workaround for propagating the include of "Python.h" to user modules to avoid "'Python.h' not found"
22+
ament_export_include_directories(${Python3_INCLUDE_DIRS})
23+
2024
if(BUILD_TESTING)
2125
find_package(ament_cmake_ros REQUIRED)
2226

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,229 @@
1+
// Copyright 2024 TIER IV
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
// NOTE(soblin): this file is intentionally inline to deal with link issue
16+
17+
#ifndef AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_
18+
#define AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_
19+
20+
#include <autoware/pyplot/patches.hpp>
21+
#include <autoware/pyplot/pyplot.hpp>
22+
23+
#include <lanelet2_core/primitives/Lanelet.h>
24+
#include <lanelet2_core/primitives/LineString.h>
25+
#include <lanelet2_core/primitives/Point.h>
26+
#include <lanelet2_core/primitives/Polygon.h>
27+
#include <pybind11/stl.h>
28+
29+
#include <algorithm>
30+
#include <optional>
31+
#include <string>
32+
#include <utility>
33+
#include <vector>
34+
35+
namespace autoware::test_utils
36+
{
37+
38+
struct PointConfig
39+
{
40+
std::optional<std::string> color{};
41+
std::optional<std::string> marker{};
42+
std::optional<double> marker_size{};
43+
};
44+
45+
struct LineConfig
46+
{
47+
static constexpr const char * default_color = "blue";
48+
static LineConfig defaults()
49+
{
50+
return LineConfig{std::string(default_color), 1.0, "solid", std::nullopt};
51+
}
52+
std::optional<std::string> color{};
53+
std::optional<double> linewidth{};
54+
std::optional<std::string> linestyle{};
55+
std::optional<std::string> label{};
56+
};
57+
58+
struct LaneConfig
59+
{
60+
static LaneConfig defaults() { return LaneConfig{std::nullopt, LineConfig::defaults(), true}; }
61+
62+
std::optional<std::string> label{};
63+
std::optional<LineConfig> line_config{};
64+
bool plot_centerline = true; //<! if true, centerline is plotted in the same style as line_config
65+
// except for {"style"_a = "dashed"}
66+
};
67+
68+
struct PolygonConfig
69+
{
70+
std::optional<double> alpha{};
71+
std::optional<std::string> color{};
72+
bool fill{true};
73+
std::optional<double> linewidth{};
74+
std::optional<PointConfig> point_config{};
75+
};
76+
77+
/**
78+
* @brief plot the linestring by `axes.plot()`
79+
* @param [in] config_opt argument for plotting the linestring. if valid, each field is used as the
80+
* kwargs
81+
*/
82+
inline void plot_lanelet2_object(
83+
const lanelet::ConstLineString3d & line, autoware::pyplot::Axes & axes,
84+
const std::optional<LineConfig> & config_opt = std::nullopt)
85+
{
86+
py::dict kwargs{};
87+
if (config_opt) {
88+
const auto & config = config_opt.value();
89+
if (config.color) {
90+
kwargs["color"] = config.color.value();
91+
}
92+
if (config.linewidth) {
93+
kwargs["linewidth"] = config.linewidth.value();
94+
}
95+
if (config.linestyle) {
96+
kwargs["linestyle"] = config.linestyle.value();
97+
}
98+
if (config.label) {
99+
kwargs["label"] = config.label.value();
100+
}
101+
}
102+
std::vector<double> xs;
103+
for (const auto & p : line) {
104+
xs.emplace_back(p.x());
105+
}
106+
std::vector<double> ys;
107+
for (const auto & p : line) {
108+
ys.emplace_back(p.y());
109+
}
110+
axes.plot(Args(xs, ys), kwargs);
111+
}
112+
113+
/**
114+
* @brief plot the left/right bounds and optionally centerline
115+
* @param [in] args used for plotting the left/right bounds as
116+
*/
117+
inline void plot_lanelet2_object(
118+
const lanelet::ConstLanelet & lanelet, autoware::pyplot::Axes & axes,
119+
const std::optional<LaneConfig> & config_opt = std::nullopt)
120+
{
121+
const auto left = lanelet.leftBound();
122+
const auto right = lanelet.rightBound();
123+
124+
const auto line_config = [&]() -> std::optional<LineConfig> {
125+
if (!config_opt) {
126+
return LineConfig{std::string(LineConfig::default_color)};
127+
}
128+
return config_opt.value().line_config;
129+
}();
130+
131+
if (config_opt) {
132+
const auto & config = config_opt.value();
133+
134+
// plot lanelet centerline
135+
if (config.plot_centerline) {
136+
auto centerline_config = [&]() -> LineConfig {
137+
if (!config.line_config) {
138+
return LineConfig{"k", std::nullopt, "dashed"};
139+
}
140+
auto cfg = config.line_config.value();
141+
cfg.color = "k";
142+
cfg.linestyle = "dashed";
143+
return cfg;
144+
}();
145+
plot_lanelet2_object(
146+
lanelet.centerline(), axes, std::make_optional<LineConfig>(std::move(centerline_config)));
147+
}
148+
149+
// plot lanelet-id
150+
const auto center = (left.front().basicPoint2d() + left.back().basicPoint2d() +
151+
right.front().basicPoint2d() + right.back().basicPoint2d()) /
152+
4.0;
153+
axes.text(Args(center.x(), center.y(), std::to_string(lanelet.id())));
154+
}
155+
156+
if (config_opt && config_opt.value().label) {
157+
auto left_line_config_for_legend = line_config ? line_config.value() : LineConfig::defaults();
158+
left_line_config_for_legend.label = config_opt.value().label.value();
159+
160+
// plot left
161+
plot_lanelet2_object(lanelet.leftBound(), axes, left_line_config_for_legend);
162+
163+
// plot right
164+
plot_lanelet2_object(lanelet.rightBound(), axes, line_config);
165+
} else {
166+
// plot left
167+
plot_lanelet2_object(lanelet.leftBound(), axes, line_config);
168+
169+
// plot right
170+
plot_lanelet2_object(lanelet.rightBound(), axes, line_config);
171+
}
172+
173+
// plot centerline direction
174+
const auto centerline_size = lanelet.centerline().size();
175+
const auto mid_index = centerline_size / 2;
176+
const auto before = static_cast<size_t>(std::max<int>(0, mid_index - 1));
177+
const auto after = static_cast<size_t>(std::min<int>(centerline_size - 1, mid_index + 1));
178+
const auto p_before = lanelet.centerline()[before];
179+
const auto p_after = lanelet.centerline()[after];
180+
const double azimuth = std::atan2(p_after.y() - p_before.y(), p_after.x() - p_before.x());
181+
const auto & mid = lanelet.centerline()[mid_index];
182+
axes.quiver(
183+
Args(mid.x(), mid.y(), std::cos(azimuth), std::sin(azimuth)), Kwargs("units"_a = "width"));
184+
}
185+
186+
/**
187+
* @brief plot the polygon as matplotlib.patches.Polygon
188+
* @param [in] config_opt argument for plotting the polygon. if valid, each field is used as the
189+
* kwargs
190+
*/
191+
inline void plot_lanelet2_object(
192+
const lanelet::ConstPolygon3d & polygon, autoware::pyplot::Axes & axes,
193+
const std::optional<PolygonConfig> & config_opt = std::nullopt)
194+
{
195+
std::vector<std::vector<double>> xy(polygon.size());
196+
for (unsigned i = 0; i < polygon.size(); ++i) {
197+
xy.at(i) = std::vector<double>({polygon[i].x(), polygon[i].y()});
198+
}
199+
py::dict kwargs;
200+
if (config_opt) {
201+
const auto & config = config_opt.value();
202+
if (config.alpha) {
203+
kwargs["alpha"] = config.alpha.value();
204+
}
205+
if (config.color) {
206+
kwargs["color"] = config.color.value();
207+
}
208+
kwargs["fill"] = config.fill;
209+
if (config.linewidth) {
210+
kwargs["linewidth"] = config.linewidth.value();
211+
}
212+
}
213+
auto poly = autoware::pyplot::Polygon(Args(xy), kwargs);
214+
axes.add_patch(Args(poly.unwrap()));
215+
}
216+
217+
/**
218+
* @brief plot the point by `axes.plot()`
219+
* @param [in] config_opt argument for plotting the point. if valid, each field is used as the
220+
* kwargs
221+
*/
222+
/*
223+
void plot_lanelet2_point(
224+
const lanelet::ConstPoint3d & point, autoware::pyplot::Axes & axes,
225+
const std::optional<PointConfig> & config_opt = std::nullopt);
226+
*/
227+
} // namespace autoware::test_utils
228+
229+
#endif // AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_

common/autoware_test_utils/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<depend>autoware_map_msgs</depend>
2424
<depend>autoware_perception_msgs</depend>
2525
<depend>autoware_planning_msgs</depend>
26+
<depend>autoware_pyplot</depend>
2627
<depend>autoware_universe_utils</depend>
2728
<depend>autoware_vehicle_msgs</depend>
2829
<depend>lanelet2_io</depend>

0 commit comments

Comments
 (0)