Skip to content

Commit b819259

Browse files
authored
Merge branch 'main' into refactor/image-proj-fus/input-rois-channel
2 parents dd60d8e + 9ce874c commit b819259

File tree

49 files changed

+6559
-798
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

49 files changed

+6559
-798
lines changed

Diff for: common/autoware_test_utils/config/sample_topic_snapshot.yaml

+6-3
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,9 @@ fields:
2424
- name: dynamic_object
2525
type: PredictedObjects # autoware_perception_msgs::msg::PredictedObjects
2626
topic: /perception/object_recognition/objects
27-
# - name: tracked_object
28-
# type: TrackedObjects # autoware_perception_msgs::msg::TrackedObjects
29-
# topic: /perception/object_recognition/tracking/objects
27+
# - name: tracked_object
28+
# type: TrackedObjects # autoware_perception_msgs::msg::TrackedObjects
29+
# topic: /perception/object_recognition/tracking/objects
30+
# - name: path_with_lane_id
31+
# type: PathWithLaneId # tier4_planning_msgs::msg::PathWithLaneId
32+
# topic: /planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id

Diff for: common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp

+13
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ using autoware_perception_msgs::msg::TrafficLightGroupArray;
5959
using autoware_planning_msgs::msg::LaneletPrimitive;
6060
using autoware_planning_msgs::msg::LaneletRoute;
6161
using autoware_planning_msgs::msg::LaneletSegment;
62+
using autoware_planning_msgs::msg::PathPoint;
6263
using builtin_interfaces::msg::Duration;
6364
using builtin_interfaces::msg::Time;
6465
using geometry_msgs::msg::Accel;
@@ -97,6 +98,9 @@ Duration parse(const YAML::Node & node);
9798
template <>
9899
Time parse(const YAML::Node & node);
99100

101+
template <>
102+
Point parse(const YAML::Node & node);
103+
100104
template <>
101105
std::vector<Point> parse(const YAML::Node & node);
102106

@@ -145,6 +149,15 @@ std::vector<PathPointWithLaneId> parse(const YAML::Node & node);
145149
template <>
146150
UUID parse(const YAML::Node & node);
147151

152+
template <>
153+
PathPoint parse(const YAML::Node & node);
154+
155+
template <>
156+
PathPointWithLaneId parse(const YAML::Node & node);
157+
158+
template <>
159+
PathWithLaneId parse(const YAML::Node & node);
160+
148161
template <>
149162
PredictedPath parse(const YAML::Node & node);
150163

Diff for: common/autoware_test_utils/include/autoware_test_utils/visualization.hpp

+108-9
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,9 @@
1919

2020
#include <autoware/pyplot/patches.hpp>
2121
#include <autoware/pyplot/pyplot.hpp>
22+
#include <autoware/universe_utils/geometry/geometry.hpp>
23+
24+
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
2225

2326
#include <lanelet2_core/primitives/Lanelet.h>
2427
#include <lanelet2_core/primitives/LineString.h>
@@ -150,7 +153,8 @@ inline void plot_lanelet2_object(
150153
const auto center = (left.front().basicPoint2d() + left.back().basicPoint2d() +
151154
right.front().basicPoint2d() + right.back().basicPoint2d()) /
152155
4.0;
153-
axes.text(Args(center.x(), center.y(), std::to_string(lanelet.id())));
156+
axes.text(
157+
Args(center.x(), center.y(), std::to_string(lanelet.id())), Kwargs("clip_on"_a = true));
154158
}
155159

156160
if (config_opt && config_opt.value().label) {
@@ -214,16 +218,111 @@ inline void plot_lanelet2_object(
214218
axes.add_patch(Args(poly.unwrap()));
215219
}
216220

221+
struct DrivableAreaConfig
222+
{
223+
static DrivableAreaConfig defaults() { return {"turquoise", 2.0}; }
224+
std::optional<std::string> color{};
225+
std::optional<double> linewidth{};
226+
};
227+
228+
struct PathWithLaneIdConfig
229+
{
230+
static PathWithLaneIdConfig defaults()
231+
{
232+
return {std::nullopt, "k", 1.0, std::nullopt, false, 1.0};
233+
}
234+
std::optional<std::string> label{};
235+
std::optional<std::string> color{};
236+
std::optional<double> linewidth{};
237+
std::optional<DrivableAreaConfig> da{};
238+
bool lane_id{}; //<! flag to plot lane_id text
239+
double quiver_size{1.0}; //<! quiver color is same as `color` or "k" if it is null
240+
};
241+
217242
/**
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
243+
* @brief plot path_with_lane_id
244+
* @param [in] config_opt if null, only the path points & quiver are plotted with "k" color.
221245
*/
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-
*/
246+
inline void plot_autoware_object(
247+
const tier4_planning_msgs::msg::PathWithLaneId & path, autoware::pyplot::Axes & axes,
248+
const std::optional<PathWithLaneIdConfig> & config_opt = std::nullopt)
249+
{
250+
py::dict kwargs{};
251+
if (config_opt) {
252+
const auto & config = config_opt.value();
253+
if (config.label) {
254+
kwargs["label"] = config.label.value();
255+
}
256+
if (config.color) {
257+
kwargs["color"] = config.color.value();
258+
}
259+
if (config.linewidth) {
260+
kwargs["linewidth"] = config.linewidth.value();
261+
}
262+
}
263+
std::vector<double> xs;
264+
std::vector<double> ys;
265+
std::vector<double> yaw_cos;
266+
std::vector<double> yaw_sin;
267+
std::vector<std::vector<lanelet::Id>> ids;
268+
const bool plot_lane_id = config_opt ? config_opt.value().lane_id : false;
269+
for (const auto & point : path.points) {
270+
xs.push_back(point.point.pose.position.x);
271+
ys.push_back(point.point.pose.position.y);
272+
const auto th = autoware::universe_utils::getRPY(point.point.pose.orientation).z;
273+
yaw_cos.push_back(std::cos(th));
274+
yaw_sin.push_back(std::sin(th));
275+
if (plot_lane_id) {
276+
ids.emplace_back();
277+
for (const auto & id : point.lane_ids) {
278+
ids.back().push_back(id);
279+
}
280+
}
281+
}
282+
// plot centerline
283+
axes.plot(Args(xs, ys), kwargs);
284+
const auto quiver_scale =
285+
config_opt ? config_opt.value().quiver_size : PathWithLaneIdConfig::defaults().quiver_size;
286+
const auto quiver_color =
287+
config_opt ? (config_opt.value().color ? config_opt.value().color.value() : "k") : "k";
288+
axes.quiver(
289+
Args(xs, ys, yaw_cos, yaw_sin), Kwargs(
290+
"angles"_a = "xy", "scale_units"_a = "xy",
291+
"scale"_a = quiver_scale, "color"_a = quiver_color));
292+
if (plot_lane_id) {
293+
for (size_t i = 0; i < xs.size(); ++i) {
294+
std::stringstream ss;
295+
const char * delimiter = "";
296+
for (const auto id : ids[i]) {
297+
ss << std::exchange(delimiter, ",") << id;
298+
}
299+
axes.text(Args(xs[i], ys[i], ss.str()), Kwargs("clip_on"_a = true));
300+
}
301+
}
302+
// plot drivable area
303+
if (config_opt && config_opt.value().da) {
304+
auto plot_boundary = [&](const decltype(path.left_bound) & points) {
305+
std::vector<double> xs;
306+
std::vector<double> ys;
307+
for (const auto & point : points) {
308+
xs.push_back(point.x);
309+
ys.push_back(point.y);
310+
}
311+
const auto & cfg = config_opt.value().da.value();
312+
py::dict kwargs{};
313+
if (cfg.color) {
314+
kwargs["color"] = cfg.color.value();
315+
}
316+
if (cfg.linewidth) {
317+
kwargs["linewidth"] = cfg.linewidth.value();
318+
}
319+
axes.plot(Args(xs, ys), kwargs);
320+
};
321+
plot_boundary(path.left_bound);
322+
plot_boundary(path.right_bound);
323+
}
324+
}
325+
227326
} // namespace autoware::test_utils
228327

229328
#endif // AUTOWARE_TEST_UTILS__VISUALIZATION_HPP_

Diff for: common/autoware_test_utils/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
99
<maintainer email="zulfaqar.azmi@tier4.jp">Zulfaqar Azmi</maintainer>
1010
<maintainer email="mamoru.sobue@tier4.jp">Mamoru Sobue</maintainer>
11+
<maintainer email="yukinari.hisaki.2@tier4.jp">Yukinari Hisaki</maintainer>
1112
<license>Apache License 2.0</license>
1213

1314
<author email="kyoichi.sugahara@tier4.jp">Kyoichi Sugahara</author>

Diff for: common/autoware_test_utils/src/mock_data_parser.cpp

+50
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,16 @@ std::array<double, 36> parse(const YAML::Node & node)
6565
return msg;
6666
}
6767

68+
template <>
69+
Point parse(const YAML::Node & node)
70+
{
71+
Point geom_point;
72+
geom_point.x = node["x"].as<double>();
73+
geom_point.y = node["y"].as<double>();
74+
geom_point.z = node["z"].as<double>();
75+
return geom_point;
76+
}
77+
6878
template <>
6979
std::vector<Point> parse(const YAML::Node & node)
7080
{
@@ -285,6 +295,46 @@ Shape parse(const YAML::Node & node)
285295
return msg;
286296
}
287297

298+
template <>
299+
PathPoint parse(const YAML::Node & node)
300+
{
301+
PathPoint point;
302+
point.pose = parse<Pose>(node["pose"]);
303+
point.longitudinal_velocity_mps = node["longitudinal_velocity_mps"].as<float>();
304+
point.lateral_velocity_mps = node["lateral_velocity_mps"].as<float>();
305+
point.heading_rate_rps = node["heading_rate_rps"].as<float>();
306+
point.is_final = node["is_final"].as<bool>();
307+
return point;
308+
}
309+
310+
template <>
311+
PathPointWithLaneId parse(const YAML::Node & node)
312+
{
313+
PathPointWithLaneId point;
314+
point.point = parse<PathPoint>(node["point"]);
315+
for (const auto & lane_id_node : node["lane_ids"]) {
316+
point.lane_ids.push_back(lane_id_node.as<int64_t>());
317+
}
318+
return point;
319+
}
320+
321+
template <>
322+
PathWithLaneId parse(const YAML::Node & node)
323+
{
324+
PathWithLaneId path;
325+
path.header = parse<Header>(node["header"]);
326+
for (const auto & point_node : node["points"]) {
327+
path.points.push_back(parse<PathPointWithLaneId>(point_node));
328+
}
329+
for (const auto & left_bound_node : node["left_bound"]) {
330+
path.left_bound.push_back(parse<Point>(left_bound_node));
331+
}
332+
for (const auto & right_bound_node : node["right_bound"]) {
333+
path.right_bound.push_back(parse<Point>(right_bound_node));
334+
}
335+
return path;
336+
}
337+
288338
template <>
289339
PredictedPath parse(const YAML::Node & node)
290340
{

Diff for: common/autoware_test_utils/src/topic_snapshot_saver.cpp

+9-2
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
2626
#include <nav_msgs/msg/odometry.hpp>
2727
#include <std_srvs/srv/empty.hpp>
28+
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
2829

2930
#include <yaml-cpp/yaml.h>
3031

@@ -46,7 +47,8 @@ using MessageType = std::variant<
4647
autoware_adapi_v1_msgs::msg::OperationModeState, // 3
4748
autoware_planning_msgs::msg::LaneletRoute, // 4
4849
autoware_perception_msgs::msg::TrafficLightGroupArray, // 5
49-
autoware_perception_msgs::msg::TrackedObjects // 6
50+
autoware_perception_msgs::msg::TrackedObjects, // 6
51+
tier4_planning_msgs::msg::PathWithLaneId // 7
5052
>;
5153

5254
std::optional<size_t> get_topic_index(const std::string & name)
@@ -72,6 +74,9 @@ std::optional<size_t> get_topic_index(const std::string & name)
7274
if (name == "TrackedObjects") {
7375
return 6;
7476
}
77+
if (name == "PathWithLaneId") {
78+
return 7;
79+
}
7580
return std::nullopt;
7681
}
7782

@@ -196,6 +201,7 @@ class TopicSnapShotSaver
196201
REGISTER_CALLBACK(4);
197202
REGISTER_CALLBACK(5);
198203
REGISTER_CALLBACK(6);
204+
REGISTER_CALLBACK(7);
199205
}
200206
}
201207

@@ -243,6 +249,7 @@ class TopicSnapShotSaver
243249
REGISTER_WRITE_TYPE(4);
244250
REGISTER_WRITE_TYPE(5);
245251
REGISTER_WRITE_TYPE(6);
252+
REGISTER_WRITE_TYPE(7);
246253
}
247254

248255
const std::string desc = std::string(R"(#
@@ -253,7 +260,7 @@ class TopicSnapShotSaver
253260
# map_path_uri: package://<package-name>/<resource-path>
254261
# fields(this is array)
255262
# - name: <field-name-for-your-yaml-of-this-topic, str>
256-
# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD}
263+
# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | PathWithLaneId | TBD}
257264
# topic: <topic-name, str>
258265
#
259266
)");

0 commit comments

Comments
 (0)