Apollo 11.0
自动驾驶开放平台
apollo::perception::lidar::TrackedObject结构体 参考

#include <tracked_object.h>

apollo::perception::lidar::TrackedObject 的协作图:

Public 成员函数

 TrackedObject ()=default
 
 TrackedObject (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose)
 
 TrackedObject (const TrackedObject &rhs)=default
 
TrackedObjectoperator= (const TrackedObject &rhs)=default
 
void Reset ()
 Reset all data
 
void Reset (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0)
 Reset all data
 
std::string ToString () const
 Transform tracked data state to string
 
void ComputeShapeFeatures ()
 Compute shape features
 
void AttachObject (base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0)
 Attach object
 
void TransformObjectCloudToWorld ()
 Transform object cloud to world
 
void CopyFrom (std::shared_ptr< TrackedObject > rhs, bool is_deep)
 Copy from tracked object
 
void ToObject (base::ObjectPtr obj_ptr) const
 Convert tracked object to base object
 
float GetVelThreshold (base::ObjectPtr obj) const
 Get vehicle threshold
 

Public 属性

std::vector< float > shape_features
 
std::vector< float > shape_features_full
 
size_t histogram_bin_size = 10
 
float association_score = 0.0f
 
bool is_fake = false
 
int track_id = -1
 
double tracking_time = 0.0
 
Eigen::Affine3d sensor_to_local_pose
 
base::ObjectPtr object_ptr
 
Eigen::Vector3d corners [4]
 
Eigen::Vector3d center
 
Eigen::Vector3d barycenter
 
Eigen::Vector3d anchor_point
 
Eigen::Vector3d detection_center
 
Eigen::Vector3d detection_corners [4]
 
Eigen::Vector3d direction
 
Eigen::Vector3d lane_direction
 
Eigen::Vector3d size
 
base::ObjectType type = base::ObjectType::UNKNOWN
 
std::vector< float > type_probs
 
bool is_background = false
 
double timestamp = 0.0
 
Eigen::Vector3d measured_barycenter_velocity
 
Eigen::Vector3d measured_center_velocity
 
Eigen::Vector3d measured_nearest_corner_velocity
 
Eigen::Vector3d measured_corners_velocity [4]
 
Eigen::Vector3d measured_history_corners_velocity [4]
 
Eigen::Vector3d measured_history_center_velocity
 
Eigen::Vector3d measured_detection_center_velocity
 
Eigen::Vector3d measured_detection_history_center_velocity
 
Eigen::Vector3d measured_detection_history_corners_velocity [4]
 
int measured_big_velocity_age
 
int boostup_need_history_size = 0
 
bool valid = false
 
bool converged = true
 
float convergence_confidence = 0.0f
 
double update_quality = 0.0
 
Eigen::Vector3d selected_measured_velocity
 
Eigen::Vector3d selected_measured_acceleration
 
Eigen::Vector3d belief_anchor_point
 
Eigen::Vector3d belief_velocity
 
Eigen::Vector3d belief_acceleration
 
Eigen::Vector3d belief_velocity_gain
 
Eigen::Matrix3d velocity_covariance
 
Eigen::Matrix3d belief_velocity_online_covariance
 
Eigen::Vector4d state
 
Eigen::Matrix4d measurement_covariance
 
Eigen::Matrix4d state_covariance
 
Eigen::Vector3d motion_score
 
Eigen::Vector3d direction_state
 
Eigen::Matrix3d direction_state_covariance
 
Eigen::Vector3d output_angular
 
double direction_convergence_confidence = 0.0
 
double direction_converged = false
 
Eigen::Vector3d output_velocity
 
Eigen::Matrix3d output_velocity_uncertainty
 
Eigen::Vector3d output_direction
 
Eigen::Vector3d output_center
 
Eigen::Vector3d output_size
 
base::SensorInfo sensor_info
 
Eigen::Vector3d global_local_offset
 

详细描述

在文件 tracked_object.h32 行定义.

构造及析构函数说明

◆ TrackedObject() [1/3]

apollo::perception::lidar::TrackedObject::TrackedObject ( )
default

◆ TrackedObject() [2/3]

apollo::perception::lidar::TrackedObject::TrackedObject ( base::ObjectPtr  obj_ptr,
const Eigen::Affine3d &  pose 
)

在文件 tracked_object.cc32 行定义.

33 {
34 AttachObject(obj_ptr, pose);
35}
void AttachObject(base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0)
Attach object

◆ TrackedObject() [3/3]

apollo::perception::lidar::TrackedObject::TrackedObject ( const TrackedObject rhs)
default

成员函数说明

◆ AttachObject()

void apollo::perception::lidar::TrackedObject::AttachObject ( base::ObjectPtr  obj_ptr,
const Eigen::Affine3d &  pose,
const Eigen::Vector3d &  global_to_local_offset = Eigen::Vector3d::Zero(),
const base::SensorInfo sensor = base::SensorInfo(),
double  timestamp = 0.0 
)

Attach object

参数
obj_ptr
pose
global_to_local_offset
sensor

在文件 tracked_object.cc37 行定义.

41 {
42 if (obj_ptr) {
43 // all state of input obj_ptr will not change except cloud world
44 object_ptr = obj_ptr;
45
47 global_local_offset = global_to_local_offset;
48 // object info to tracked object
49 center = pose * object_ptr->center;
50 const PointFCloud& cloud = (object_ptr->lidar_supplement).cloud;
51 barycenter = (algorithm::CalculateCentroid(cloud)).cast<double>();
52 barycenter = pose * barycenter;
54
55 // object-detection center
56 float detection_center_x = obj_ptr->lidar_supplement.detections[0];
57 float detection_center_y = obj_ptr->lidar_supplement.detections[1];
58 float detection_center_z = obj_ptr->lidar_supplement.detections[2];
59 float detection_size_x = obj_ptr->lidar_supplement.detections[3];
60 float detection_size_y = obj_ptr->lidar_supplement.detections[4];
61 float detection_size_z = obj_ptr->lidar_supplement.detections[5];
62 float detection_theta = obj_ptr->lidar_supplement.detections[6];
63 Eigen::Vector3d model_center_lidar = Eigen::Vector3d(detection_center_x,
64 detection_center_y, detection_center_z);
65 detection_center = pose * model_center_lidar;
66
67 // object-detection center/size/direction -> corners
68 Eigen::Matrix<float, 8, 1> corners;
70 detection_center_x, detection_center_y, detection_center_z,
71 detection_size_x, detection_size_y, detection_size_z,
72 detection_theta, &corners);
73 for (size_t i = 0; i < 4; i++) {
74 Eigen::Vector3d detection_cor = Eigen::Vector3d(
75 static_cast<double>(corners[2 * i]),
76 static_cast<double>(corners[2 * i + 1]), detection_center_z);
77 detection_corners[i] = pose * detection_cor;
78 }
79
80 Eigen::Matrix3d rotation = pose.rotation();
81 direction = rotation * object_ptr->direction.cast<double>();
83 size = object_ptr->size.cast<double>();
84 type = object_ptr->type;
85 type_probs = object_ptr->type_probs;
86 is_background = object_ptr->lidar_supplement.is_background;
87
88 base::PointDCloud& cloud_world = (object_ptr->lidar_supplement).cloud_world;
89 cloud_world.clear();
90 cloud_world.resize(cloud.size());
91 for (size_t i = 0; i < cloud.size(); ++i) {
92 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
93 Eigen::Vector3d pt_world = pose * pt;
94 cloud_world[i].x = pt_world(0);
95 cloud_world[i].y = pt_world(1);
96 cloud_world[i].z = pt_world(2);
97 cloud_world[i].intensity = cloud[i].intensity;
98 }
99 // memcpy(&(cloud_world.points_height(0)), &(cloud.points_height(0)),
100 // sizeof(float) * cloud.size());
101 for (size_t i = 0; i < cloud.size(); ++i) {
102 cloud_world.SetPointHeight(i, cloud.points_height(i));
103 }
104 // other belief information keep as Reset()
105 selected_measured_velocity = Eigen::Vector3d::Zero();
106 selected_measured_acceleration = Eigen::Vector3d::Zero();
108 belief_velocity = Eigen::Vector3d::Zero();
109 belief_acceleration = Eigen::Vector3d::Zero();
110
111 direction_state = Eigen::Vector3d::Zero();
112 direction_state_covariance = Eigen::Matrix3d::Zero();
113 output_angular = Eigen::Vector3d::Zero();
115 direction_converged = false;
116
117 output_velocity = Eigen::Vector3d::Zero();
118 output_velocity_uncertainty = Eigen::Matrix3d::Zero();
122
123 sensor_info = sensor;
124 this->timestamp = timestamp;
125 }
126}
Eigen::Matrix< T, 3, 1 > CalculateCentroid(const base::AttributePointCloud< base::Point< T > > &cloud)
Definition common.h:134
void CalculateCornersFromCenter(Type center_x, Type center_y, Type center_z, Type size_x, Type size_y, Type size_z, Type theta, Eigen::Matrix< Type, 8, 1 > *corners)
Definition common.h:366
AttributePointCloud< PointD > PointDCloud
apollo::perception::base::PointCloud< PointF > PointFCloud

◆ ComputeShapeFeatures()

void apollo::perception::lidar::TrackedObject::ComputeShapeFeatures ( )

Compute shape features

在文件 tracked_object.cc296 行定义.

296 {
297 // Compute object's shape feature
298 // 1. check whether shape feature is ready
299 // 2. compute object's shape feature
301 FeatureDescriptor fd(&(object_ptr->lidar_supplement.cloud));
302 fd.ComputeHistogram(static_cast<int>(histogram_bin_size),
303 shape_features_full.data());
304
305 size_t feature_len = histogram_bin_size * 3;
306 shape_features.clear();
307 shape_features.resize(feature_len);
308 for (size_t i = 0; i < feature_len; ++i) {
310 }
311}

◆ CopyFrom()

void apollo::perception::lidar::TrackedObject::CopyFrom ( std::shared_ptr< TrackedObject rhs,
bool  is_deep 
)

Copy from tracked object

参数
rhs
is_deep

◆ GetVelThreshold()

float apollo::perception::lidar::TrackedObject::GetVelThreshold ( base::ObjectPtr  obj) const

Get vehicle threshold

参数
obj
返回
float

在文件 tracked_object.cc238 行定义.

238 {
239 if (obj->type == base::ObjectType::VEHICLE) {
240 return 0.99f;
241 }
242 return 0.0f;
243}

◆ operator=()

TrackedObject & apollo::perception::lidar::TrackedObject::operator= ( const TrackedObject rhs)
default

◆ Reset() [1/2]

void apollo::perception::lidar::TrackedObject::Reset ( )

Reset all data

在文件 tracked_object.cc145 行定义.

145 {
146 object_ptr.reset();
147 sensor_to_local_pose = Eigen::Affine3d::Identity();
148
149 // measurement reset
150 for (int i = 0; i < 4; ++i) {
151 corners[i] = Eigen::Vector3d::Zero();
152 detection_corners[i] = Eigen::Vector3d::Zero();
153 measured_corners_velocity[i] = Eigen::Vector3d::Zero();
154 measured_history_corners_velocity[i] = Eigen::Vector3d::Zero();
155 measured_detection_history_corners_velocity[i] = Eigen::Vector3d::Zero();
156 }
157 center = Eigen::Vector3d::Zero();
158 barycenter = Eigen::Vector3d::Zero();
159 anchor_point = Eigen::Vector3d::Zero();
160 detection_center = Eigen::Vector3d::Zero();
161 measured_barycenter_velocity = Eigen::Vector3d::Zero();
162 measured_center_velocity = Eigen::Vector3d::Zero();
163 measured_nearest_corner_velocity = Eigen::Vector3d::Zero();
164 measured_history_center_velocity = Eigen::Vector3d::Zero();
165 measured_detection_center_velocity = Eigen::Vector3d::Zero();
166 measured_detection_history_center_velocity = Eigen::Vector3d::Zero();
168 direction = Eigen::Vector3d::Zero();
169 lane_direction = Eigen::Vector3d::Zero();
170 size = Eigen::Vector3d::Zero();
172 type_probs.assign(static_cast<int>(base::ObjectType::MAX_OBJECT_TYPE), 0.0f);
173 is_background = false;
174 shape_features.clear();
175 shape_features_full.clear();
177 association_score = 0.0;
178 is_fake = false;
179 track_id = -1;
180 tracking_time = 0.0;
181
182 // filter reset
184 valid = false;
185 converged = true;
187 update_quality = 0.0;
189 selected_measured_acceleration = Eigen::Vector3d::Zero();
193 belief_velocity_gain = Eigen::Vector3d::Zero();
194 velocity_covariance = Eigen::Matrix3d::Zero();
195 belief_velocity_online_covariance = Eigen::Matrix3d::Zero();
196
197 state = Eigen::Vector4d::Zero();
198 measurement_covariance = Eigen::Matrix4d::Zero();
199 state_covariance = Eigen::Matrix4d::Zero();
200
201 motion_score = Eigen::Vector3d(1, 1, 1);
202
203 direction_state = Eigen::Vector3d::Zero();
204 direction_state_covariance = Eigen::Matrix3d::Zero();
205 output_angular = Eigen::Vector3d::Zero();
207 direction_converged = false;
208
209 // output reset
215
216 // sensor info reset
218 timestamp = 0.0;
219}
Eigen::Vector3d measured_detection_history_corners_velocity[4]

◆ Reset() [2/2]

void apollo::perception::lidar::TrackedObject::Reset ( base::ObjectPtr  obj_ptr,
const Eigen::Affine3d &  pose,
const Eigen::Vector3d &  global_to_local_offset = Eigen::Vector3d::Zero(),
const base::SensorInfo sensor = base::SensorInfo(),
double  timestamp = 0.0 
)

Reset all data

参数
obj_ptr
pose
global_to_local_offset
sensor

在文件 tracked_object.cc221 行定义.

223 {
224 Reset();
225 AttachObject(obj_ptr, pose, global_to_local_offset, sensor, timestamp);
226}

◆ ToObject()

void apollo::perception::lidar::TrackedObject::ToObject ( base::ObjectPtr  obj_ptr) const

Convert tracked object to base object

参数
obj_ptr

在文件 tracked_object.cc245 行定义.

245 {
246 *obj = *object_ptr;
247 // obj id keep default
248 // obj polygon calculate outside, because
249 /* 1. if ConvexHull2D as member variable:
250 constructor time consume a little large
251 2. if ConvexHull2D as static or global variable:
252 need mutex time consume in multi threads
253 what a pity!
254 */
255 obj->direction = output_direction.cast<float>();
256 // obj theta_variance not calculate in tracker, keep default
257 obj->center = output_center;
258 // obj center_uncertainty not calculate in tracker, keep default
259 obj->size = output_size.cast<float>();
260 // obj size_varuance not calculate in tracker, keep default
261 obj->anchor_point = belief_anchor_point;
262 obj->type = type;
263 // obj type_probs calculate in tracker
264 obj->type_probs = type_probs;
265 // obj confidence not calculate in tracker, keep default
266 obj->track_id = track_id;
267 obj->velocity = output_velocity.cast<float>();
268 obj->velocity_uncertainty = output_velocity_uncertainty.cast<float>();
269 obj->velocity_converged = converged;
270 obj->tracking_time = tracking_time;
271 if (obj->velocity.norm() > GetVelThreshold(obj)) {
272 obj->theta = std::atan2(obj->velocity[1], obj->velocity[0]);
273 } else {
274 obj->theta = std::atan2(obj->direction[1], obj->direction[0]);
275 }
276 // obj latest_tracked_time not calculate in tracker, keep default
277 // obj car_light not calculate in tracker, keep default
278 // obj lidar_supplement cloud_world has passed in *obj = *object_ptr
279 // obj lidar_supplement other elements not calculate in tracker, keep default
280 // obj radar_supplement not calculate in tracker, keep default
281 // obj camera_supplement not calculate in tracker, keep default
282}
float GetVelThreshold(base::ObjectPtr obj) const
Get vehicle threshold

◆ ToString()

std::string apollo::perception::lidar::TrackedObject::ToString ( ) const

Transform tracked data state to string

返回
std::string

在文件 tracked_object.cc284 行定义.

284 {
285 // std::string txt;
286 // return txt;
287 std::ostringstream oos;
288 oos << "obj id: " << object_ptr->id << ", track_id: " << object_ptr->track_id
289 << ", bary_center: (" << barycenter[0] << "," << barycenter[1] << ","
290 << barycenter[2] << ")"
291 << ", lane_direction: (" << lane_direction[0] << "," << lane_direction[1]
292 << "," << lane_direction[2] << ")";
293 return oos.str();
294}

◆ TransformObjectCloudToWorld()

void apollo::perception::lidar::TrackedObject::TransformObjectCloudToWorld ( )

Transform object cloud to world

在文件 tracked_object.cc128 行定义.

128 {
129 const base::PointFCloud& cloud = (object_ptr->lidar_supplement).cloud;
130 base::PointDCloud& cloud_world = (object_ptr->lidar_supplement).cloud_world;
131 cloud_world.clear();
132 cloud_world.resize(cloud.size());
133 for (size_t i = 0; i < cloud.size(); ++i) {
134 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
135 Eigen::Vector3d pt_world = sensor_to_local_pose * pt;
136 cloud_world[i].x = pt_world(0);
137 cloud_world[i].y = pt_world(1);
138 cloud_world[i].z = pt_world(2);
139 cloud_world[i].intensity = cloud[i].intensity;
140 }
141 memcpy(&cloud_world.points_height(0), &cloud.points_height(0),
142 sizeof(float) * cloud.size());
143}
AttributePointCloud< PointF > PointFCloud

类成员变量说明

◆ anchor_point

Eigen::Vector3d apollo::perception::lidar::TrackedObject::anchor_point

在文件 tracked_object.h141 行定义.

◆ association_score

float apollo::perception::lidar::TrackedObject::association_score = 0.0f

在文件 tracked_object.h119 行定义.

◆ barycenter

Eigen::Vector3d apollo::perception::lidar::TrackedObject::barycenter

在文件 tracked_object.h140 行定义.

◆ belief_acceleration

Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_acceleration

在文件 tracked_object.h185 行定义.

◆ belief_anchor_point

Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_anchor_point

在文件 tracked_object.h183 行定义.

◆ belief_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_velocity

在文件 tracked_object.h184 行定义.

◆ belief_velocity_gain

Eigen::Vector3d apollo::perception::lidar::TrackedObject::belief_velocity_gain

在文件 tracked_object.h186 行定义.

◆ belief_velocity_online_covariance

Eigen::Matrix3d apollo::perception::lidar::TrackedObject::belief_velocity_online_covariance

在文件 tracked_object.h190 行定义.

◆ boostup_need_history_size

int apollo::perception::lidar::TrackedObject::boostup_need_history_size = 0

在文件 tracked_object.h176 行定义.

◆ center

Eigen::Vector3d apollo::perception::lidar::TrackedObject::center

在文件 tracked_object.h139 行定义.

◆ converged

bool apollo::perception::lidar::TrackedObject::converged = true

在文件 tracked_object.h178 行定义.

◆ convergence_confidence

float apollo::perception::lidar::TrackedObject::convergence_confidence = 0.0f

在文件 tracked_object.h179 行定义.

◆ corners

Eigen::Vector3d apollo::perception::lidar::TrackedObject::corners[4]

在文件 tracked_object.h138 行定义.

◆ detection_center

Eigen::Vector3d apollo::perception::lidar::TrackedObject::detection_center

在文件 tracked_object.h143 行定义.

◆ detection_corners

Eigen::Vector3d apollo::perception::lidar::TrackedObject::detection_corners[4]

在文件 tracked_object.h144 行定义.

◆ direction

Eigen::Vector3d apollo::perception::lidar::TrackedObject::direction

在文件 tracked_object.h147 行定义.

◆ direction_converged

double apollo::perception::lidar::TrackedObject::direction_converged = false

在文件 tracked_object.h213 行定义.

◆ direction_convergence_confidence

double apollo::perception::lidar::TrackedObject::direction_convergence_confidence = 0.0

在文件 tracked_object.h212 行定义.

◆ direction_state

Eigen::Vector3d apollo::perception::lidar::TrackedObject::direction_state

在文件 tracked_object.h208 行定义.

◆ direction_state_covariance

Eigen::Matrix3d apollo::perception::lidar::TrackedObject::direction_state_covariance

在文件 tracked_object.h209 行定义.

◆ global_local_offset

Eigen::Vector3d apollo::perception::lidar::TrackedObject::global_local_offset

在文件 tracked_object.h225 行定义.

◆ histogram_bin_size

size_t apollo::perception::lidar::TrackedObject::histogram_bin_size = 10

在文件 tracked_object.h116 行定义.

◆ is_background

bool apollo::perception::lidar::TrackedObject::is_background = false

在文件 tracked_object.h154 行定义.

◆ is_fake

bool apollo::perception::lidar::TrackedObject::is_fake = false

在文件 tracked_object.h124 行定义.

◆ lane_direction

Eigen::Vector3d apollo::perception::lidar::TrackedObject::lane_direction

在文件 tracked_object.h148 行定义.

◆ measured_barycenter_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_barycenter_velocity

在文件 tracked_object.h161 行定义.

◆ measured_big_velocity_age

int apollo::perception::lidar::TrackedObject::measured_big_velocity_age

在文件 tracked_object.h170 行定义.

◆ measured_center_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_center_velocity

在文件 tracked_object.h162 行定义.

◆ measured_corners_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_corners_velocity[4]

在文件 tracked_object.h164 行定义.

◆ measured_detection_center_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_center_velocity

在文件 tracked_object.h167 行定义.

◆ measured_detection_history_center_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_history_center_velocity

在文件 tracked_object.h168 行定义.

◆ measured_detection_history_corners_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_detection_history_corners_velocity[4]

在文件 tracked_object.h169 行定义.

◆ measured_history_center_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_history_center_velocity

在文件 tracked_object.h166 行定义.

◆ measured_history_corners_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_history_corners_velocity[4]

在文件 tracked_object.h165 行定义.

◆ measured_nearest_corner_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::measured_nearest_corner_velocity

在文件 tracked_object.h163 行定义.

◆ measurement_covariance

Eigen::Matrix4d apollo::perception::lidar::TrackedObject::measurement_covariance

在文件 tracked_object.h194 行定义.

◆ motion_score

Eigen::Vector3d apollo::perception::lidar::TrackedObject::motion_score

在文件 tracked_object.h203 行定义.

◆ object_ptr

base::ObjectPtr apollo::perception::lidar::TrackedObject::object_ptr

在文件 tracked_object.h136 行定义.

◆ output_angular

Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_angular

在文件 tracked_object.h210 行定义.

◆ output_center

Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_center

在文件 tracked_object.h221 行定义.

◆ output_direction

Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_direction

在文件 tracked_object.h220 行定义.

◆ output_size

Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_size

在文件 tracked_object.h222 行定义.

◆ output_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::output_velocity

在文件 tracked_object.h218 行定义.

◆ output_velocity_uncertainty

Eigen::Matrix3d apollo::perception::lidar::TrackedObject::output_velocity_uncertainty

在文件 tracked_object.h219 行定义.

◆ selected_measured_acceleration

Eigen::Vector3d apollo::perception::lidar::TrackedObject::selected_measured_acceleration

在文件 tracked_object.h182 行定义.

◆ selected_measured_velocity

Eigen::Vector3d apollo::perception::lidar::TrackedObject::selected_measured_velocity

在文件 tracked_object.h181 行定义.

◆ sensor_info

base::SensorInfo apollo::perception::lidar::TrackedObject::sensor_info

在文件 tracked_object.h223 行定义.

◆ sensor_to_local_pose

Eigen::Affine3d apollo::perception::lidar::TrackedObject::sensor_to_local_pose

在文件 tracked_object.h131 行定义.

◆ shape_features

std::vector<float> apollo::perception::lidar::TrackedObject::shape_features

在文件 tracked_object.h114 行定义.

◆ shape_features_full

std::vector<float> apollo::perception::lidar::TrackedObject::shape_features_full

在文件 tracked_object.h115 行定义.

◆ size

Eigen::Vector3d apollo::perception::lidar::TrackedObject::size

在文件 tracked_object.h149 行定义.

◆ state

Eigen::Vector4d apollo::perception::lidar::TrackedObject::state

在文件 tracked_object.h193 行定义.

◆ state_covariance

Eigen::Matrix4d apollo::perception::lidar::TrackedObject::state_covariance

在文件 tracked_object.h195 行定义.

◆ timestamp

double apollo::perception::lidar::TrackedObject::timestamp = 0.0

在文件 tracked_object.h156 行定义.

◆ track_id

int apollo::perception::lidar::TrackedObject::track_id = -1

在文件 tracked_object.h125 行定义.

◆ tracking_time

double apollo::perception::lidar::TrackedObject::tracking_time = 0.0

在文件 tracked_object.h126 行定义.

◆ type

base::ObjectType apollo::perception::lidar::TrackedObject::type = base::ObjectType::UNKNOWN

在文件 tracked_object.h151 行定义.

◆ type_probs

std::vector<float> apollo::perception::lidar::TrackedObject::type_probs

在文件 tracked_object.h153 行定义.

◆ update_quality

double apollo::perception::lidar::TrackedObject::update_quality = 0.0

在文件 tracked_object.h180 行定义.

◆ valid

bool apollo::perception::lidar::TrackedObject::valid = false

在文件 tracked_object.h177 行定义.

◆ velocity_covariance

Eigen::Matrix3d apollo::perception::lidar::TrackedObject::velocity_covariance

在文件 tracked_object.h189 行定义.


该结构体的文档由以下文件生成: