Apollo 10.0
自动驾驶开放平台
object_supplement.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16#pragma once
17
18#include <limits>
19#include <memory>
20#include <string>
21#include <vector>
22
23#include <boost/circular_buffer.hpp>
24
30
31namespace apollo {
32namespace perception {
33namespace base {
34
36 void Reset() {
38 on_use = false;
39 cloud.clear();
41 is_fp = false;
42 fp_prob = 0.f;
43 is_background = false;
44 is_in_roi = false;
46 height_above_ground = std::numeric_limits<float>::max();
47 raw_probs.clear();
49 detections.clear();
50 }
51 // @brief orientation estimateed indicator
53 // @brief valid only for on_use = true
54 bool on_use = false;
55 // @brief index of the cloud of the object
56 std::vector<int> point_ids;
57 // @brief cloud of the object in lidar coordinates
59 // @brief cloud of the object in world coordinates
61 // @brief background indicator
62 bool is_background = false;
63 // @brief either object is clustered or from detection model
64 bool is_clustered = false;
65 // @brief object semantic type
67 // @brief object dynamic state for scene-flow model
69 // @brief false positive indicator
70 bool is_fp = false;
71 // @brief false positive probability
72 float fp_prob = 0.f;
73 // @brief whether this object is in roi
74 bool is_in_roi = false;
75 // @brief number of cloud points in roi
77 // @brief object height above ground
78 float height_above_ground = std::numeric_limits<float>::max();
79
80 // @brief raw probability of each classification method
81 std::vector<std::vector<float>> raw_probs;
82 std::vector<std::string> raw_classification_methods;
83
84 // @brief object-detection original output
85 std::vector<float> detections = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
86
87 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88};
89typedef std::shared_ptr<LidarObjectSupplement> LidarObjectSupplementPtr;
90typedef std::shared_ptr<const LidarObjectSupplement>
92
94 void Reset() {
96 on_use = false;
97 cloud.clear();
98 cloud_world.clear();
99 is_fp = false;
100 fp_prob = 0.f;
101 is_background = false;
102 is_in_roi = false;
104 height_above_ground = std::numeric_limits<float>::max();
105 raw_probs.clear();
107 }
108 // @brief orientation estimateed indicator
110 // @brief valid only for on_use = true
111 bool on_use = false;
112 // @brief index of the cloud of the object
113 std::vector<int> point_ids;
114 // @brief cloud of the object in radar coordinates
116 // @brief cloud of the object in world coordinates
118 // @brief background indicator
119 bool is_background = false;
120 // @brief false positive indicator
121 bool is_fp = false;
122 // @brief false positive probability
123 float fp_prob = 0.f;
124 // @brief whether this object is in roi
125 bool is_in_roi = false;
126 // @brief number of cloud points in roi
128 // @brief object height above ground
129 float height_above_ground = std::numeric_limits<float>::max();
130
131 // @brief raw probability of each classification method
132 std::vector<std::vector<float>> raw_probs;
133 std::vector<std::string> raw_classification_methods;
134
135 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
136};
137typedef std::shared_ptr<Radar4dObjectSupplement> Radar4dObjectSupplementPtr;
138typedef std::shared_ptr<const Radar4dObjectSupplement>
140
142 void Reset() {
143 on_use = false;
144 range = 0.0f;
145 angle = 0.0f;
148 radial_velocity = 0.0f;
149 }
150 // @brief valid only for on_use = true
151 bool on_use = false;
152 /* @brief (range, angle) in radar polar coordinate system
153 x for forward and y for left
154 */
155 float range = 0.0f;
156 float angle = 0.0f;
157
160 float radial_velocity = 0.0f;
161};
162
163typedef std::shared_ptr<RadarObjectSupplement> RadarObjectSupplementPtr;
164typedef std::shared_ptr<const RadarObjectSupplement>
166
169
170 void Reset() {
171 on_use = false;
172 sensor_name.clear();
173 local_track_id = -1;
174 pts8.clear();
175 object_feature.clear();
176 alpha = 0.0;
177 box = BBox2D<float>();
181 local_center = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
183 visual_type_probs.resize(
184 static_cast<int>(VisualObjectType::MAX_OBJECT_TYPE), 0);
185
186 area_id = 0;
187 visible_ratios[0] = visible_ratios[1] = 0;
188 visible_ratios[2] = visible_ratios[3] = 0;
189 cut_off_ratios[0] = cut_off_ratios[1] = 0;
190 cut_off_ratios[2] = cut_off_ratios[3] = 0;
191 }
192
193 // @brief valid only for on_use = true
194 bool on_use = false;
195
196 // @brief camera sensor name
197 std::string sensor_name;
198
199 // @brief 2d box
201
202 // @brief projected 2d box
204
205 // @brief local track id
207
208 // @brief 2Dto3D, pts8.resize(16), x, y...
209 std::vector<float> pts8;
210
211 // @brief front box
213
214 // @brief back box
216 std::vector<float> object_feature;
217
218 // @brief alpha angle from KITTI: Observation angle of object, in [-pi..pi]
219 double alpha = 0.0;
221 double truncated_vertical = 0.0;
222 // @brief center in camera coordinate system
223 Eigen::Vector3f local_center = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
224
225 // @brief visual object type, only used in camera module
227 std::vector<float> visual_type_probs;
228
229 //----------------------------------------------------------------
230 // area ID, corner ID and face ID
231 //----------------------------------------------------------------
232 // 8 | 1 | 2 a
233 // --------- 0-----1 ^
234 // | | | | |
235 // 7 | 0 | 3 d| |b
236 // | | | |
237 // --------- 3-----2
238 // 6 | 5 | 4 c
239 //----------------------------------------------------------------
241 // @brief visible ratios
243 // @brief cut off ratios on width, length (3D)
244 // cut off ratios on left, right (2D)
246
247 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
248};
249typedef std::shared_ptr<CameraObjectSupplement> CameraObjectSupplementPtr;
250typedef std::shared_ptr<const CameraObjectSupplement>
252
253typedef Eigen::Matrix4f MotionType;
255 float roll_rate = 0;
256 float pitch_rate = 0;
257 float yaw_rate = 0;
258 float velocity = 0;
259 float velocity_x = 0;
260 float velocity_y = 0;
261 float velocity_z = 0;
262 double time_ts = 0; // time stamp
263 double time_d = 0; // time stamp difference in image
264 MotionType motion = MotionType::Identity(); // Motion Matrix
265
266 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
267};
268
269typedef boost::circular_buffer<VehicleStatus> MotionBuffer;
270typedef std::shared_ptr<MotionBuffer> MotionBufferPtr;
271typedef std::shared_ptr<const MotionBuffer> MotionBufferConstPtr;
272
274 float yaw_delta; // azimuth angle change
277 float velocity_x; // east
278 float velocity_y; // north
279 float velocity_z; // up
280 double time_ts; // time stamp
281 double time_d; // time stamp difference in image
282 Eigen::Matrix4f motion3d; // 3-d Motion Matrix
283
284 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
285};
286
287typedef boost::circular_buffer<Vehicle3DStatus> Motion3DBuffer;
288typedef std::shared_ptr<Motion3DBuffer> Motion3DBufferPtr;
289typedef std::shared_ptr<const Motion3DBuffer> Motion3DBufferConstPtr;
290
292 void Reset() {
293 sensor_id = "unknonw_sensor";
294 timestamp = 0.0;
295 track_id = -1;
296 center = Eigen::Vector3d(0, 0, 0);
297 theta = 0.0f;
298 size = Eigen::Vector3f(0, 0, 0);
299 velocity = Eigen::Vector3f(0, 0, 0);
301 box = BBox2D<float>();
302 }
303
304 std::string sensor_id = "unknown_sensor";
305 double timestamp = 0.0;
306 int track_id = -1;
307 float theta = 0.0f;
308 Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0);
309 Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0);
310 Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
312 // @brief only for camera measurement
314
315 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
316};
317
327
328} // namespace base
329} // namespace perception
330} // namespace apollo
std::vector< EigenType, Eigen::aligned_allocator< EigenType > > EigenVector
Definition eigen_defs.h:33
std::shared_ptr< RadarObjectSupplement > RadarObjectSupplementPtr
boost::circular_buffer< VehicleStatus > MotionBuffer
std::shared_ptr< const MotionBuffer > MotionBufferConstPtr
std::shared_ptr< MotionBuffer > MotionBufferPtr
std::shared_ptr< Motion3DBuffer > Motion3DBufferPtr
std::shared_ptr< const RadarObjectSupplement > RadarObjectSupplementConstPtr
std::shared_ptr< const CameraObjectSupplement > CameraObjectSupplementConstPtr
std::shared_ptr< LidarObjectSupplement > LidarObjectSupplementPtr
boost::circular_buffer< Vehicle3DStatus > Motion3DBuffer
std::shared_ptr< const Motion3DBuffer > Motion3DBufferConstPtr
std::shared_ptr< CameraObjectSupplement > CameraObjectSupplementPtr
std::shared_ptr< const Radar4dObjectSupplement > Radar4dObjectSupplementConstPtr
std::shared_ptr< Radar4dObjectSupplement > Radar4dObjectSupplementPtr
std::shared_ptr< const LidarObjectSupplement > LidarObjectSupplementConstPtr
class register implement
Definition arena_queue.h:37
apollo::common::EigenVector< SensorObjectMeasurement > measurements
base::AttributePointCloud< PointD > cloud_world
base::AttributePointCloud< PointF > cloud
std::vector< std::vector< float > > raw_probs
base::AttributeRadarPointCloud< RadarPointF > cloud
std::vector< std::vector< float > > raw_probs
base::AttributeRadarPointCloud< RadarPointD > cloud_world