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