Apollo  v5.5.0
Open source self driving car software
object_supplement.h
Go to the documentation of this file.
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 <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "boost/circular_buffer.hpp"
23 
27 
28 namespace apollo {
29 namespace perception {
30 namespace base {
31 
32 struct alignas(16) LidarObjectSupplement {
33  void Reset() {
34  is_orientation_ready = false;
35  on_use = false;
36  cloud.clear();
37  cloud_world.clear();
38  is_fp = false;
39  fp_prob = 0.f;
40  is_background = false;
41  is_in_roi = false;
43  height_above_ground = FLT_MAX;
44  raw_probs.clear();
46  }
47  // @brief orientation estimateed indicator
48  bool is_orientation_ready = false;
49  // @brief valid only for on_use = true
50  bool on_use = false;
51  // @brief cloud of the object in lidar coordinates
53  // @brief cloud of the object in world coordinates
55  // @brief background indicator
56  bool is_background = false;
57  // @brief false positive indicator
58  bool is_fp = false;
59  // @brief false positive probability
60  float fp_prob = 0.f;
61  // @brief whether this object is in roi
62  bool is_in_roi = false;
63  // @brief number of cloud points in roi
64  size_t num_points_in_roi = 0;
65  // @brief object height above ground
66  float height_above_ground = FLT_MAX;
67 
68  // @brief raw probability of each classification method
69  std::vector<std::vector<float>> raw_probs;
70  std::vector<std::string> raw_classification_methods;
71 };
72 typedef std::shared_ptr<LidarObjectSupplement> LidarObjectSupplementPtr;
73 typedef std::shared_ptr<const LidarObjectSupplement>
75 
76 struct alignas(16) RadarObjectSupplement {
77  void Reset() {
78  on_use = false;
79  range = 0.0f;
80  angle = 0.0f;
81  relative_radial_velocity = 0.0f;
82  relative_tangential_velocity = 0.0f;
83  radial_velocity = 0.0f;
84  }
85  // @brief valid only for on_use = true
86  bool on_use = false;
87  /* @brief (range, angle) in radar polar coordinate system
88  x for forward and y for left
89  */
90  float range = 0.0f;
91  float angle = 0.0f;
92 
93  float relative_radial_velocity = 0.0f;
94  float relative_tangential_velocity = 0.0f;
95  float radial_velocity = 0.0f;
96 };
97 
98 typedef std::shared_ptr<RadarObjectSupplement> RadarObjectSupplementPtr;
99 typedef std::shared_ptr<const RadarObjectSupplement>
101 
102 struct alignas(16) CameraObjectSupplement {
104 
105  void Reset() {
106  on_use = false;
107  sensor_name.clear();
108  local_track_id = -1;
109  pts8.clear();
110  object_feature.clear();
111  alpha = 0.0;
112  box = BBox2D<float>();
113  projected_box = BBox2D<float>();
114  front_box = BBox2D<float>();
115  back_box = BBox2D<float>();
116  local_center = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
117  visual_type = VisualObjectType::MAX_OBJECT_TYPE;
118  visual_type_probs.resize(
119  static_cast<int>(VisualObjectType::MAX_OBJECT_TYPE), 0);
120 
121  area_id = 0;
122  visible_ratios[0] = visible_ratios[1] = 0;
123  visible_ratios[2] = visible_ratios[3] = 0;
124  cut_off_ratios[0] = cut_off_ratios[1] = 0;
125  cut_off_ratios[2] = cut_off_ratios[3] = 0;
126  }
127 
128  // @brief valid only for on_use = true
129  bool on_use = false;
130 
131  // @brief camera sensor name
132  std::string sensor_name;
133 
134  // @brief 2d box
136 
137  // @brief projected 2d box
139 
140  // @brief local track id
141  int local_track_id = -1;
142 
143  // @brief 2Dto3D, pts8.resize(16), x, y...
144  std::vector<float> pts8;
145 
146  // @brief front box
148 
149  // @brief back box
151  std::vector<float> object_feature;
152 
153  // @brief alpha angle from KITTI: Observation angle of object, in [-pi..pi]
154  double alpha = 0.0;
155  double truncated_horizontal = 0.0;
156  double truncated_vertical = 0.0;
157  // @brief center in camera coordinate system
158  Eigen::Vector3f local_center = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
159 
160  // @brief visual object type, only used in camera module
162  std::vector<float> visual_type_probs;
163 
164  //----------------------------------------------------------------
165  // area ID, corner ID and face ID
166  //----------------------------------------------------------------
167  // 8 | 1 | 2 a
168  // --------- 0-----1 ^
169  // | | | | |
170  // 7 | 0 | 3 d| |b
171  // | | | |
172  // --------- 3-----2
173  // 6 | 5 | 4 c
174  //----------------------------------------------------------------
175  int area_id;
176  // @brief visible ratios
177  float visible_ratios[4];
178  // @brief cut off ratios on width, length (3D)
179  // cut off ratios on left, right (2D)
180  float cut_off_ratios[4];
181 };
182 typedef std::shared_ptr<CameraObjectSupplement> CameraObjectSupplementPtr;
183 typedef std::shared_ptr<const CameraObjectSupplement>
185 
186 typedef Eigen::Matrix4f MotionType;
187 struct alignas(16) VehicleStatus {
188  float roll_rate = 0;
189  float pitch_rate = 0;
190  float yaw_rate = 0;
191  float velocity = 0;
192  float velocity_x = 0;
193  float velocity_y = 0;
194  float velocity_z = 0;
195  double time_ts = 0; // time stamp
196  double time_d = 0; // time stamp difference in image
197  MotionType motion = MotionType::Identity(); // Motion Matrix
198 };
199 
200 typedef boost::circular_buffer<VehicleStatus> MotionBuffer;
201 typedef std::shared_ptr<MotionBuffer> MotionBufferPtr;
202 typedef std::shared_ptr<const MotionBuffer> MotionBufferConstPtr;
203 
204 struct alignas(16) Vehicle3DStatus {
205  float yaw_delta; // azimuth angle change
206  float pitch_delta;
207  float roll_delta;
208  float velocity_x; // east
209  float velocity_y; // north
210  float velocity_z; // up
211  double time_ts; // time stamp
212  double time_d; // time stamp difference in image
213  Eigen::Matrix4f motion3d; // 3-d Motion Matrix
214 };
215 
216 typedef boost::circular_buffer<Vehicle3DStatus> Motion3DBuffer;
217 typedef std::shared_ptr<Motion3DBuffer> Motion3DBufferPtr;
218 typedef std::shared_ptr<const Motion3DBuffer> Motion3DBufferConstPtr;
219 
221  void Reset() {
222  sensor_id = "unknonw_sensor";
223  timestamp = 0.0;
224  track_id = -1;
225  center = Eigen::Vector3d(0, 0, 0);
226  theta = 0.0f;
227  size = Eigen::Vector3f(0, 0, 0);
228  velocity = Eigen::Vector3f(0, 0, 0);
229  type = ObjectType::UNKNOWN;
230  box = BBox2D<float>();
231  }
232 
233  std::string sensor_id = "unknown_sensor";
234  double timestamp = 0.0;
235  int track_id = -1;
236  Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0);
237  float theta = 0.0f;
238  Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0);
239  Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
241  // @brief only for camera measurement
243 };
244 
245 struct alignas(16) FusionObjectSupplement {
246  FusionObjectSupplement() { measurements.reserve(5); }
247  void Reset() {
248  on_use = false;
249  measurements.clear();
250  }
251  bool on_use = false;
252  std::vector<SensorObjectMeasurement> measurements;
253 };
254 
255 } // namespace base
256 } // namespace perception
257 } // namespace apollo
void Reset()
Definition: object_supplement.h:221
float yaw_delta
Definition: object_supplement.h:205
float velocity_z
Definition: object_supplement.h:210
Eigen::Matrix4f motion3d
Definition: object_supplement.h:213
std::vector< SensorObjectMeasurement > measurements
Definition: object_supplement.h:252
std::vector< std::string > raw_classification_methods
Definition: object_supplement.h:70
std::shared_ptr< Motion3DBuffer > Motion3DBufferPtr
Definition: object_supplement.h:217
Definition: blob.h:72
bool is_orientation_ready
Definition: object_supplement.h:48
Definition: object_supplement.h:245
float fp_prob
Definition: object_supplement.h:60
BBox2D< float > box
Definition: object_supplement.h:135
std::shared_ptr< const Motion3DBuffer > Motion3DBufferConstPtr
Definition: object_supplement.h:218
BBox2D< float > projected_box
Definition: object_supplement.h:138
Definition: object_supplement.h:204
float velocity_x
Definition: object_supplement.h:208
double time_ts
Definition: object_supplement.h:211
bool is_fp
Definition: object_supplement.h:58
std::shared_ptr< const MotionBuffer > MotionBufferConstPtr
Definition: object_supplement.h:202
Definition: object_supplement.h:220
std::vector< std::vector< float > > raw_probs
Definition: object_supplement.h:69
base::AttributePointCloud< PointF > cloud
Definition: object_supplement.h:52
CameraObjectSupplement()
Definition: object_supplement.h:103
Eigen::Matrix4f MotionType
Definition: object_supplement.h:186
float pitch_delta
Definition: object_supplement.h:206
Definition: object_supplement.h:32
float velocity_y
Definition: object_supplement.h:209
std::vector< float > pts8
Definition: object_supplement.h:144
void Reset()
Definition: object_supplement.h:105
size_t num_points_in_roi
Definition: object_supplement.h:64
BBox2D< float > box
Definition: object_supplement.h:242
bool on_use
Definition: object_supplement.h:50
float height_above_ground
Definition: object_supplement.h:66
bool is_background
Definition: object_supplement.h:56
BBox2D< float > front_box
Definition: object_supplement.h:147
Definition: object_supplement.h:187
std::shared_ptr< const RadarObjectSupplement > RadarObjectSupplementConstPtr
Definition: object_supplement.h:100
void Reset()
Definition: object_supplement.h:33
void Reset()
Definition: object_supplement.h:247
std::shared_ptr< CameraObjectSupplement > CameraObjectSupplementPtr
Definition: object_supplement.h:182
std::shared_ptr< const LidarObjectSupplement > LidarObjectSupplementConstPtr
Definition: object_supplement.h:74
float roll_delta
Definition: object_supplement.h:207
std::vector< float > object_feature
Definition: object_supplement.h:151
std::shared_ptr< MotionBuffer > MotionBufferPtr
Definition: object_supplement.h:201
Definition: object_supplement.h:76
base::AttributePointCloud< PointD > cloud_world
Definition: object_supplement.h:54
std::shared_ptr< LidarObjectSupplement > LidarObjectSupplementPtr
Definition: object_supplement.h:72
int area_id
Definition: object_supplement.h:175
boost::circular_buffer< Vehicle3DStatus > Motion3DBuffer
Definition: object_supplement.h:216
double time_d
Definition: object_supplement.h:212
std::shared_ptr< const CameraObjectSupplement > CameraObjectSupplementConstPtr
Definition: object_supplement.h:184
Definition: object_supplement.h:102
bool is_in_roi
Definition: object_supplement.h:62
BBox2D< float > back_box
Definition: object_supplement.h:150
VisualObjectType
Definition: object_types.h:48
FusionObjectSupplement()
Definition: object_supplement.h:246
std::string sensor_name
Definition: object_supplement.h:132
ObjectType
Definition: object_types.h:26
std::vector< float > visual_type_probs
Definition: object_supplement.h:162
void Reset()
Definition: object_supplement.h:77
std::shared_ptr< RadarObjectSupplement > RadarObjectSupplementPtr
Definition: object_supplement.h:98
boost::circular_buffer< VehicleStatus > MotionBuffer
Definition: object_supplement.h:200