Apollo 10.0
自动驾驶开放平台
apollo::perception::base::Object结构体 参考

#include <object.h>

apollo::perception::base::Object 的协作图:

Public 成员函数

 Object ()
 
std::string ToString () const
 
void Reset ()
 

Public 属性

int id = -1
 
PointCloud< PointDpolygon
 
Eigen::Vector3f direction = Eigen::Vector3f(1, 0, 0)
 
float theta = 0.0f
 
float theta_variance = 0.0f
 
Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0)
 
Eigen::Matrix3f center_uncertainty
 
Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0)
 
Eigen::Vector3f size_variance = Eigen::Vector3f(0, 0, 0)
 
Eigen::Vector3d anchor_point = Eigen::Vector3d(0, 0, 0)
 
ObjectType type = ObjectType::UNKNOWN
 
std::vector< float > type_probs
 
ObjectSubType sub_type = ObjectSubType::UNKNOWN
 
std::vector< float > sub_type_probs
 
float confidence = 1.0f
 
bool is_front_critical = false
 
int track_id = -1
 
Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0)
 
Eigen::Matrix3f velocity_uncertainty
 
bool velocity_converged = true
 
float velocity_confidence = 1.0f
 
Eigen::Vector3f acceleration = Eigen::Vector3f(0, 0, 0)
 
Eigen::Matrix3f acceleration_uncertainty
 
double tracking_time = 0.0
 
double latest_tracked_time = 0.0
 
MotionState motion_state = MotionState::UNKNOWN
 
std::array< Eigen::Vector3d, 100 > drops
 
std::size_t drop_num = 0
 
bool b_cipv = false
 
CarLight car_light
 
LidarObjectSupplement lidar_supplement
 
Radar4dObjectSupplement radar4d_supplement
 
RadarObjectSupplement radar_supplement
 
CameraObjectSupplement camera_supplement
 
FusionObjectSupplement fusion_supplement
 

详细描述

在文件 object.h34 行定义.

构造及析构函数说明

◆ Object()

apollo::perception::base::Object::Object ( )

在文件 object.cc23 行定义.

23 {
24 center_uncertainty << 0.0f, 0, 0, 0, 0.0f, 0, 0, 0, 0.0f;
25 velocity_uncertainty << 0.0f, 0, 0, 0, 0.0f, 0, 0, 0, 0.0f;
26 acceleration_uncertainty << 0.0f, 0, 0, 0, 0.0f, 0, 0, 0, 0.0f;
27 type_probs.resize(static_cast<int>(ObjectType::MAX_OBJECT_TYPE), 0);
28 sub_type_probs.resize(static_cast<int>(ObjectSubType::MAX_OBJECT_TYPE), 0.0f);
29 b_cipv = false;
30// feature.reset();
31}
Eigen::Matrix3f velocity_uncertainty
Definition object.h:90
std::vector< float > sub_type_probs
Definition object.h:76
std::vector< float > type_probs
Definition object.h:71
Eigen::Matrix3f acceleration_uncertainty
Definition object.h:98
Eigen::Matrix3f center_uncertainty
Definition object.h:58

成员函数说明

◆ Reset()

void apollo::perception::base::Object::Reset ( )

在文件 object.cc33 行定义.

33 {
34 id = -1;
35 polygon.clear();
36 direction = Eigen::Vector3f(1.0f, 0.0f, 0.0f);
37 theta = 0.0f;
38 theta_variance = 0.0f;
39 center = Eigen::Vector3d(0.0, 0.0, 0.0);
40 center_uncertainty << 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f;
41
42 size = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
43 size_variance = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
44 anchor_point = Eigen::Vector3d(0.0, 0.0, 0.0);
46 type_probs.assign(static_cast<int>(ObjectType::MAX_OBJECT_TYPE), 0.0f);
48 sub_type_probs.assign(static_cast<int>(ObjectSubType::MAX_OBJECT_TYPE), 0.0f);
49
50 confidence = 1.0f;
51
52 is_front_critical = false;
53
54 track_id = -1;
55 velocity = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
56 velocity_uncertainty << 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f;
57 velocity_converged = true;
59 acceleration = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
60 acceleration_uncertainty << 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f,
61 0.0f;
62
63 tracking_time = 0.0;
65
68
74// feature.reset();
75}
CameraObjectSupplement camera_supplement
Definition object.h:118
Eigen::Vector3f acceleration
Definition object.h:96
Eigen::Vector3f direction
Definition object.h:47
PointCloud< PointD > polygon
Definition object.h:43
Eigen::Vector3f size_variance
Definition object.h:64
FusionObjectSupplement fusion_supplement
Definition object.h:119
RadarObjectSupplement radar_supplement
Definition object.h:117
Radar4dObjectSupplement radar4d_supplement
Definition object.h:116
LidarObjectSupplement lidar_supplement
Definition object.h:115
Eigen::Vector3d anchor_point
Definition object.h:66

◆ ToString()

std::string apollo::perception::base::Object::ToString ( ) const

在文件 object.cc77 行定义.

77 {
78 std::ostringstream oss;
79 oss << "Object [id: " << id << ", track_id: " << track_id << ", direction: ("
80 << direction[0] << "," << direction[1] << "," << direction[2]
81 << "), theta: " << theta << ", theta_variance: " << theta_variance
82 << ", center: (" << center[0] << "," << center[1] << "," << center[2]
83 << ")"
84 << ", center_uncertainty: (" << center_uncertainty(0, 0) << ","
85 << center_uncertainty(0, 1) << "," << center_uncertainty(0, 2) << ","
86 << center_uncertainty(1, 0) << "," << center_uncertainty(1, 1) << ","
87 << center_uncertainty(1, 2) << "," << center_uncertainty(2, 0) << ","
88 << center_uncertainty(2, 1) << "," << center_uncertainty(2, 2)
89 << "), size: (" << size[0] << "," << size[1] << "," << size[2]
90 << "), size_variance: (" << size_variance[0] << "," << size_variance[1]
91 << "," << size_variance[2] << "), anchor_point: (" << anchor_point[0]
92 << "," << anchor_point[1] << "," << anchor_point[2]
93 << "), type: " << static_cast<int>(type) << ", confidence: " << confidence
94 << ", track_id: " << track_id << ", velocity: (" << velocity[0] << ","
95 << velocity[1] << "," << velocity[2]
96 << "), velocity_confidence: " << velocity_confidence
97 << ", acceleration: (" << acceleration[0] << "," << acceleration[1] << ","
98 << acceleration[2] << "), tracking_time: " << tracking_time
99 << ", latest_tracked_time: " << latest_tracked_time;
100 return oss.str();
101}

类成员变量说明

◆ acceleration

Eigen::Vector3f apollo::perception::base::Object::acceleration = Eigen::Vector3f(0, 0, 0)

在文件 object.h96 行定义.

◆ acceleration_uncertainty

Eigen::Matrix3f apollo::perception::base::Object::acceleration_uncertainty

在文件 object.h98 行定义.

◆ anchor_point

Eigen::Vector3d apollo::perception::base::Object::anchor_point = Eigen::Vector3d(0, 0, 0)

在文件 object.h66 行定义.

◆ b_cipv

bool apollo::perception::base::Object::b_cipv = false

在文件 object.h111 行定义.

◆ camera_supplement

CameraObjectSupplement apollo::perception::base::Object::camera_supplement

在文件 object.h118 行定义.

◆ car_light

CarLight apollo::perception::base::Object::car_light

在文件 object.h113 行定义.

◆ center

Eigen::Vector3d apollo::perception::base::Object::center = Eigen::Vector3d(0, 0, 0)

在文件 object.h56 行定义.

◆ center_uncertainty

Eigen::Matrix3f apollo::perception::base::Object::center_uncertainty

在文件 object.h58 行定义.

◆ confidence

float apollo::perception::base::Object::confidence = 1.0f

在文件 object.h79 行定义.

◆ direction

Eigen::Vector3f apollo::perception::base::Object::direction = Eigen::Vector3f(1, 0, 0)

在文件 object.h47 行定义.

◆ drop_num

std::size_t apollo::perception::base::Object::drop_num = 0

在文件 object.h109 行定义.

◆ drops

std::array<Eigen::Vector3d, 100> apollo::perception::base::Object::drops

在文件 object.h108 行定义.

◆ fusion_supplement

FusionObjectSupplement apollo::perception::base::Object::fusion_supplement

在文件 object.h119 行定义.

◆ id

int apollo::perception::base::Object::id = -1

在文件 object.h40 行定义.

◆ is_front_critical

bool apollo::perception::base::Object::is_front_critical = false

在文件 object.h82 行定义.

◆ latest_tracked_time

double apollo::perception::base::Object::latest_tracked_time = 0.0

在文件 object.h103 行定义.

◆ lidar_supplement

LidarObjectSupplement apollo::perception::base::Object::lidar_supplement

在文件 object.h115 行定义.

◆ motion_state

MotionState apollo::perception::base::Object::motion_state = MotionState::UNKNOWN

在文件 object.h106 行定义.

◆ polygon

PointCloud<PointD> apollo::perception::base::Object::polygon

在文件 object.h43 行定义.

◆ radar4d_supplement

Radar4dObjectSupplement apollo::perception::base::Object::radar4d_supplement

在文件 object.h116 行定义.

◆ radar_supplement

RadarObjectSupplement apollo::perception::base::Object::radar_supplement

在文件 object.h117 行定义.

◆ size

Eigen::Vector3f apollo::perception::base::Object::size = Eigen::Vector3f(0, 0, 0)

在文件 object.h62 行定义.

◆ size_variance

Eigen::Vector3f apollo::perception::base::Object::size_variance = Eigen::Vector3f(0, 0, 0)

在文件 object.h64 行定义.

◆ sub_type

ObjectSubType apollo::perception::base::Object::sub_type = ObjectSubType::UNKNOWN

在文件 object.h74 行定义.

◆ sub_type_probs

std::vector<float> apollo::perception::base::Object::sub_type_probs

在文件 object.h76 行定义.

◆ theta

float apollo::perception::base::Object::theta = 0.0f

在文件 object.h52 行定义.

◆ theta_variance

float apollo::perception::base::Object::theta_variance = 0.0f

在文件 object.h54 行定义.

◆ track_id

int apollo::perception::base::Object::track_id = -1

在文件 object.h86 行定义.

◆ tracking_time

double apollo::perception::base::Object::tracking_time = 0.0

在文件 object.h101 行定义.

◆ type

ObjectType apollo::perception::base::Object::type = ObjectType::UNKNOWN

在文件 object.h69 行定义.

◆ type_probs

std::vector<float> apollo::perception::base::Object::type_probs

在文件 object.h71 行定义.

◆ velocity

Eigen::Vector3f apollo::perception::base::Object::velocity = Eigen::Vector3f(0, 0, 0)

在文件 object.h88 行定义.

◆ velocity_confidence

float apollo::perception::base::Object::velocity_confidence = 1.0f

在文件 object.h94 行定义.

◆ velocity_converged

bool apollo::perception::base::Object::velocity_converged = true

在文件 object.h92 行定义.

◆ velocity_uncertainty

Eigen::Matrix3f apollo::perception::base::Object::velocity_uncertainty

在文件 object.h90 行定义.


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