@@ -38,34 +38,74 @@ using autoware::universe_utils::createDefaultMarker;
38
38
using autoware::universe_utils::createMarkerScale;
39
39
using geometry_msgs::msg::Point ;
40
40
41
- MarkerArray showAllValidLaneChangePath (const std::vector<LaneChangePath> & lanes, std::string && ns)
41
+ MarkerArray showAllValidLaneChangePath (
42
+ const std::vector<LaneChangePath> & lane_change_paths, std::string && ns)
42
43
{
43
- if (lanes .empty ()) {
44
+ if (lane_change_paths .empty ()) {
44
45
return MarkerArray{};
45
46
}
46
47
47
48
MarkerArray marker_array;
48
- int32_t id{0 };
49
49
const auto current_time{rclcpp::Clock{RCL_ROS_TIME}.now ()};
50
50
51
51
const auto colors = colors::colors_list ();
52
- const auto loop_size = std::min (lanes .size (), colors.size ());
52
+ const auto loop_size = std::min (lane_change_paths .size (), colors.size ());
53
53
marker_array.markers .reserve (loop_size);
54
54
55
+ const auto info_prep_to_string =
56
+ [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string {
57
+ std::ostringstream ss_text;
58
+ ss_text << std::setprecision (3 ) << " vel: " << info.velocity .prepare
59
+ << " [m/s] | lon_acc: " << info.longitudinal_acceleration .prepare
60
+ << " [m/s2] | t: " << info.duration .prepare << " [s] | L: " << info.length .prepare
61
+ << " [m]" ;
62
+ return ss_text.str ();
63
+ };
64
+
65
+ const auto info_lc_to_string =
66
+ [](const autoware::behavior_path_planner::lane_change::Info & info) -> std::string {
67
+ std::ostringstream ss_text;
68
+ ss_text << std::setprecision (3 ) << " vel: " << info.velocity .lane_changing
69
+ << " [m/s] | lon_acc: " << info.longitudinal_acceleration .lane_changing
70
+ << " [m/s2] | lat_acc: " << info.lateral_acceleration
71
+ << " [m/s2] | t: " << info.duration .lane_changing
72
+ << " [s] | L: " << info.length .lane_changing << " [m]" ;
73
+ return ss_text.str ();
74
+ };
75
+
55
76
for (std::size_t idx = 0 ; idx < loop_size; ++idx) {
56
- if (lanes.at (idx).path .points .empty ()) {
77
+ int32_t id{0 };
78
+ const auto & lc_path = lane_change_paths.at (idx);
79
+ if (lc_path.path .points .empty ()) {
57
80
continue ;
58
81
}
59
-
82
+ std::string ns_with_idx = ns + " [ " + std::to_string (idx) + " ] " ;
60
83
const auto & color = colors.at (idx);
61
- Marker marker = createDefaultMarker (
62
- " map" , current_time, ns, ++id, Marker::LINE_STRIP, createMarkerScale (0.1 , 0.1 , 0.0 ), color);
63
- marker.points .reserve (lanes.at (idx).path .points .size ());
84
+ const auto & points = lc_path.path .points ;
85
+ auto marker = createDefaultMarker (
86
+ " map" , current_time, ns_with_idx, ++id, Marker::LINE_STRIP, createMarkerScale (0.1 , 0.1 , 0.0 ),
87
+ color);
88
+ marker.points .reserve (points.size ());
64
89
65
- for (const auto & point : lanes. at (idx). path . points ) {
90
+ for (const auto & point : points) {
66
91
marker.points .push_back (point.point .pose .position );
67
92
}
68
93
94
+ auto text_marker = createDefaultMarker (
95
+ " map" , current_time, ns_with_idx, ++id, visualization_msgs::msg::Marker::TEXT_VIEW_FACING,
96
+ createMarkerScale (0.1 , 0.1 , 0.8 ), colors::yellow ());
97
+ const auto prep_idx = points.size () / 4 ;
98
+ text_marker.pose = points.at (prep_idx).point .pose ;
99
+ text_marker.pose .position .z += 2.0 ;
100
+ text_marker.text = info_prep_to_string (lc_path.info );
101
+ marker_array.markers .push_back (text_marker);
102
+
103
+ const auto lc_idx = points.size () / 2 ;
104
+ text_marker.id = ++id;
105
+ text_marker.pose = points.at (lc_idx).point .pose ;
106
+ text_marker.text = info_lc_to_string (lc_path.info );
107
+ marker_array.markers .push_back (text_marker);
108
+
69
109
marker_array.markers .push_back (marker);
70
110
}
71
111
return marker_array;
0 commit comments