You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardexpand all lines: common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp
+5-1
Original file line number
Diff line number
Diff line change
@@ -57,6 +57,9 @@ struct ObjectPropertyValues
57
57
float alpha{0.999F};
58
58
};
59
59
60
+
// Control object marker visualization
61
+
enumclassObjectFillType { Skeleton, Fill };
62
+
60
63
// Map defining colors according to value of label field in ObjectClassification msg
Copy file name to clipboardexpand all lines: common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp
+13-1
Original file line number
Diff line number
Diff line change
@@ -112,6 +112,12 @@ class AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC ObjectPolygonDisplayBase
> If you launch the planning simulator without adding the `tier4_simulated_clock_rviz_plugin`, your simulation will not be running. You'll not even be able to place the initial and the goal poses.
23
+
24
+
2. Start rviz and select panels/Add new panel.
14
25
15
-
1. Start rviz and select panels/Add new panel.
16
26

17
-
2. Select tier4_clock_rviz_plugin/SimulatedClock and press OK.
27
+
28
+
3. Select tier4_clock_rviz_plugin/SimulatedClock and press OK.
Copy file name to clipboardexpand all lines: control/autonomous_emergency_braking/README.md
+27
Original file line number
Diff line number
Diff line change
@@ -108,6 +108,33 @@ After Noise filtering, it performs a geometric collision check to determine whet
108
108
109
109
Finally, the vertex that is closest to the ego vehicle is chosen as the candidate for collision checking: Since rss distance is used to judge if a collision will happen or not, if the closest vertex to the ego is deemed to be safe, the rest of the vertices (and the points in the clusters) will also be safe.
110
110
111
+
#### Obstacle velocity estimation
112
+
113
+
Once the position of the closest obstacle/point is determined, the AEB modules uses the history of previously detected objects to estimate the closest object speed using the following equations:
114
+
115
+
$$
116
+
d_{t} = o_{time stamp} - prev_{time stamp}
117
+
$$
118
+
119
+
$$
120
+
d_{pos} = norm(o_{pos} - prev_{pos})
121
+
$$
122
+
123
+
$$
124
+
v_{norm} = d_{pos} / d_{t}
125
+
$$
126
+
127
+
Where $o_{time stamp}$ and $prev_{time stamp}$ are the timestamps of the point clouds used to detect the current closest object and the closest object of the previous point cloud frame, and $o_{pos}$ and $prev_{pos}$ are the positions of those objects, respectively.
128
+
129
+
Finally, the velocity vector is compared against the ego's predicted path to get the longitudinal velocity $v_{obj}$:
130
+
131
+
$$
132
+
v_{obj} = v_{norm} * Cos(yaw_{diff}) + v_{ego}
133
+
$$
134
+
135
+
where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector $$v_{pos} = o_{pos} - prev_{pos} $$ and $v_{ego}$ is the ego's speed, which accounts for the movement of points caused by the ego moving and not the object.
136
+
All these equations are performed disregarding the z axis (in 2D).
137
+
111
138
### 4. Collision check with target obstacles
112
139
113
140
In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as:
0 commit comments