@@ -32,13 +32,12 @@ visualization_msgs::msg::Marker get_base_marker()
32
32
base_marker.pose .orientation = tier4_autoware_utils::createMarkerOrientation (0 , 0 , 0 , 1.0 );
33
33
base_marker.scale = tier4_autoware_utils::createMarkerScale (0.1 , 0.1 , 0.1 );
34
34
base_marker.color = tier4_autoware_utils::createMarkerColor (1.0 , 0.1 , 0.1 , 0.5 );
35
- base_marker.lifetime = rclcpp::Duration::from_seconds (0.5 );
36
35
return base_marker;
37
36
}
38
37
} // namespace
39
38
void add_footprint_markers (
40
39
visualization_msgs::msg::MarkerArray & debug_marker_array,
41
- const lanelet::BasicPolygons2d & footprints, const double z)
40
+ const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb )
42
41
{
43
42
auto debug_marker = get_base_marker ();
44
43
debug_marker.ns = " footprints" ;
@@ -52,12 +51,14 @@ void add_footprint_markers(
52
51
debug_marker.id ++;
53
52
debug_marker.points .clear ();
54
53
}
54
+ for (; debug_marker.id < static_cast <int >(prev_nb); ++debug_marker.id )
55
+ debug_marker_array.markers .push_back (debug_marker);
55
56
}
56
57
57
58
void add_current_overlap_marker (
58
59
visualization_msgs::msg::MarkerArray & debug_marker_array,
59
60
const lanelet::BasicPolygon2d & current_footprint,
60
- const lanelet::ConstLanelets & current_overlapped_lanelets, const double z)
61
+ const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb )
61
62
{
62
63
auto debug_marker = get_base_marker ();
63
64
debug_marker.ns = " current_overlap" ;
@@ -80,12 +81,14 @@ void add_current_overlap_marker(
80
81
debug_marker_array.markers .push_back (debug_marker);
81
82
debug_marker.id ++;
82
83
}
84
+ for (; debug_marker.id < static_cast <int >(prev_nb); ++debug_marker.id )
85
+ debug_marker_array.markers .push_back (debug_marker);
83
86
}
84
87
85
88
void add_lanelet_markers (
86
89
visualization_msgs::msg::MarkerArray & debug_marker_array,
87
90
const lanelet::ConstLanelets & lanelets, const std::string & ns,
88
- const std_msgs::msg::ColorRGBA & color)
91
+ const std_msgs::msg::ColorRGBA & color, const size_t prev_nb )
89
92
{
90
93
auto debug_marker = get_base_marker ();
91
94
debug_marker.ns = ns;
@@ -101,6 +104,82 @@ void add_lanelet_markers(
101
104
debug_marker_array.markers .push_back (debug_marker);
102
105
debug_marker.id ++;
103
106
}
107
+ debug_marker.action = debug_marker.DELETE ;
108
+ for (; debug_marker.id < static_cast <int >(prev_nb); ++debug_marker.id )
109
+ debug_marker_array.markers .push_back (debug_marker);
110
+ }
111
+
112
+ void add_range_markers (
113
+ visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges,
114
+ const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t first_ego_idx,
115
+ const double z, const size_t prev_nb)
116
+ {
117
+ auto debug_marker = get_base_marker ();
118
+ debug_marker.ns = " ranges" ;
119
+ debug_marker.color = tier4_autoware_utils::createMarkerColor (0.2 , 0.9 , 0.1 , 0.5 );
120
+ for (const auto & range : ranges) {
121
+ debug_marker.points .clear ();
122
+ debug_marker.points .push_back (
123
+ path.points [first_ego_idx + range.entering_path_idx ].point .pose .position );
124
+ debug_marker.points .push_back (tier4_autoware_utils::createMarkerPosition (
125
+ range.entering_point .x (), range.entering_point .y (), z));
126
+ for (const auto & overlap : range.debug .overlaps ) {
127
+ debug_marker.points .push_back (tier4_autoware_utils::createMarkerPosition (
128
+ overlap.min_overlap_point .x (), overlap.min_overlap_point .y (), z));
129
+ debug_marker.points .push_back (tier4_autoware_utils::createMarkerPosition (
130
+ overlap.max_overlap_point .x (), overlap.max_overlap_point .y (), z));
131
+ }
132
+ debug_marker.points .push_back (tier4_autoware_utils::createMarkerPosition (
133
+ range.exiting_point .x (), range.exiting_point .y (), z));
134
+ debug_marker.points .push_back (
135
+ path.points [first_ego_idx + range.exiting_path_idx ].point .pose .position );
136
+ debug_marker_array.markers .push_back (debug_marker);
137
+ debug_marker.id ++;
138
+ }
139
+ debug_marker.action = debug_marker.DELETE ;
140
+ for (; debug_marker.id < static_cast <int >(prev_nb); ++debug_marker.id )
141
+ debug_marker_array.markers .push_back (debug_marker);
142
+ debug_marker.action = debug_marker.ADD ;
143
+ debug_marker.id = 0 ;
144
+ debug_marker.ns = " decisions" ;
145
+ debug_marker.color = tier4_autoware_utils::createMarkerColor (0.9 , 0.1 , 0.1 , 1.0 );
146
+ debug_marker.points .clear ();
147
+ for (const auto & range : ranges) {
148
+ debug_marker.type = debug_marker.LINE_STRIP ;
149
+ if (range.debug .decision ) {
150
+ debug_marker.points .push_back (tier4_autoware_utils::createMarkerPosition (
151
+ range.entering_point .x (), range.entering_point .y (), z));
152
+ debug_marker.points .push_back (
153
+ range.debug .object ->kinematics .initial_pose_with_covariance .pose .position );
154
+ }
155
+ debug_marker_array.markers .push_back (debug_marker);
156
+ debug_marker.points .clear ();
157
+ debug_marker.id ++;
158
+
159
+ debug_marker.type = debug_marker.TEXT_VIEW_FACING ;
160
+ debug_marker.pose .position .x = range.entering_point .x ();
161
+ debug_marker.pose .position .y = range.entering_point .y ();
162
+ debug_marker.pose .position .z = z;
163
+ std::stringstream ss;
164
+ ss << " Ego: " << range.debug .times .ego .enter_time << " - " << range.debug .times .ego .exit_time
165
+ << " \n " ;
166
+ if (range.debug .object ) {
167
+ debug_marker.pose .position .x +=
168
+ range.debug .object ->kinematics .initial_pose_with_covariance .pose .position .x ;
169
+ debug_marker.pose .position .y +=
170
+ range.debug .object ->kinematics .initial_pose_with_covariance .pose .position .y ;
171
+ debug_marker.pose .position .x /= 2 ;
172
+ debug_marker.pose .position .y /= 2 ;
173
+ ss << " Obj: " << range.debug .times .object .enter_time << " - "
174
+ << range.debug .times .object .exit_time << " \n " ;
175
+ }
176
+ debug_marker.scale .z = 1.0 ;
177
+ debug_marker.text = ss.str ();
178
+ debug_marker_array.markers .push_back (debug_marker);
179
+ debug_marker.id ++;
180
+ }
181
+ for (; debug_marker.id < static_cast <int >(prev_nb); ++debug_marker.id )
182
+ debug_marker_array.markers .push_back (debug_marker);
104
183
}
105
184
106
185
} // namespace behavior_velocity_planner::out_of_lane::debug
0 commit comments