Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::LocationExporter类 参考

Export info about localziation in rosbag. 更多...

#include <location_exporter.h>

apollo::localization::msf::LocationExporter 的协作图:

Public 成员函数

 LocationExporter (const std::string &loc_file_folder)
 
 ~LocationExporter ()
 
void GnssLocCallback (const std::string &msg)
 
void LidarLocCallback (const std::string &msg)
 
void FusionLocCallback (const std::string &msg)
 
void OdometryLocCallback (const std::string &msg)
 

详细描述

Export info about localziation in rosbag.

在文件 location_exporter.h29 行定义.

构造及析构函数说明

◆ LocationExporter()

apollo::localization::msf::LocationExporter::LocationExporter ( const std::string &  loc_file_folder)
explicit

在文件 location_exporter.cc29 行定义.

29 {
30 gnss_loc_file_ = loc_file_folder + "/gnss_loc.txt";
31 lidar_loc_file_ = loc_file_folder + "/lidar_loc.txt";
32 fusion_loc_file_ = loc_file_folder + "/fusion_loc.txt";
33 odometry_loc_file_ = loc_file_folder + "/odometry_loc.txt";
34
35 if ((gnss_loc_file_handle_ = fopen(gnss_loc_file_.c_str(), "a")) == nullptr) {
36 AERROR << "Cannot open gnss localization file!";
37 }
38
39 if ((lidar_loc_file_handle_ = fopen(lidar_loc_file_.c_str(), "a")) ==
40 nullptr) {
41 AERROR << "Cannot open lidar localization file!";
42 }
43
44 if ((fusion_loc_file_handle_ = fopen(fusion_loc_file_.c_str(), "a")) ==
45 nullptr) {
46 AERROR << "Cannot open fusion localization file!";
47 }
48
49 if ((odometry_loc_file_handle_ = fopen(odometry_loc_file_.c_str(), "a")) ==
50 nullptr) {
51 AERROR << "Cannot open odometry localization file!";
52 }
53}
#define AERROR
Definition log.h:44

◆ ~LocationExporter()

apollo::localization::msf::LocationExporter::~LocationExporter ( )

在文件 location_exporter.cc55 行定义.

55 {
56 if (gnss_loc_file_handle_ != nullptr) {
57 fclose(gnss_loc_file_handle_);
58 }
59
60 if (lidar_loc_file_handle_ != nullptr) {
61 fclose(lidar_loc_file_handle_);
62 }
63
64 if (fusion_loc_file_handle_ != nullptr) {
65 fclose(fusion_loc_file_handle_);
66 }
67
68 if (odometry_loc_file_handle_ != nullptr) {
69 fclose(odometry_loc_file_handle_);
70 }
71}

成员函数说明

◆ FusionLocCallback()

void apollo::localization::msf::LocationExporter::FusionLocCallback ( const std::string &  msg)

在文件 location_exporter.cc134 行定义.

134 {
135 AINFO << "Fusion location callback.";
136 LocalizationEstimate msg;
137 msg.ParseFromString(msg_string);
138 static unsigned int index = 1;
139
140 double timestamp = msg.measurement_time();
141 double x = msg.pose().position().x();
142 double y = msg.pose().position().y();
143 double z = msg.pose().position().z();
144
145 double qx = msg.pose().orientation().qx();
146 double qy = msg.pose().orientation().qy();
147 double qz = msg.pose().orientation().qz();
148 double qw = msg.pose().orientation().qw();
149
150 // apollo::common::math::EulerAnglesZXY<double> euler(
151 // qw, qx, qy, qz);
152 // double roll = euler.roll();
153 // double pitch = euler.pitch();
154 // double yaw = euler.yaw();
155
156 double std_x = msg.uncertainty().position_std_dev().x();
157 double std_y = msg.uncertainty().position_std_dev().y();
158 double std_z = msg.uncertainty().position_std_dev().z();
159
160 fprintf(fusion_loc_file_handle_,
161 "%u %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", index, timestamp,
162 x, y, z, qx, qy, qz, qw, std_x, std_y, std_z);
163
164 ++index;
165}
#define AINFO
Definition log.h:42

◆ GnssLocCallback()

void apollo::localization::msf::LocationExporter::GnssLocCallback ( const std::string &  msg)

在文件 location_exporter.cc73 行定义.

73 {
74 AINFO << "GNSS location callback.";
75 LocalizationEstimate msg;
76 msg.ParseFromString(msg_string);
77
78 static unsigned int index = 1;
79
80 double timestamp = msg.measurement_time();
81 double x = msg.pose().position().x();
82 double y = msg.pose().position().y();
83 double z = msg.pose().position().z();
84
85 double qx = msg.pose().orientation().qx();
86 double qy = msg.pose().orientation().qy();
87 double qz = msg.pose().orientation().qz();
88 double qw = msg.pose().orientation().qw();
89
90 double std_x = msg.uncertainty().position_std_dev().x();
91 double std_y = msg.uncertainty().position_std_dev().y();
92 double std_z = msg.uncertainty().position_std_dev().z();
93
94 fprintf(gnss_loc_file_handle_,
95 "%u %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", index, timestamp,
96 x, y, z, qx, qy, qz, qw, std_x, std_y, std_z);
97
98 ++index;
99}

◆ LidarLocCallback()

void apollo::localization::msf::LocationExporter::LidarLocCallback ( const std::string &  msg)

在文件 location_exporter.cc101 行定义.

101 {
102 AINFO << "Lidar location callback.";
103 LocalizationEstimate msg;
104 msg.ParseFromString(msg_string);
105 static unsigned int index = 1;
106
107 double timestamp = msg.measurement_time();
108 double x = msg.pose().position().x();
109 double y = msg.pose().position().y();
110 double z = msg.pose().position().z();
111
112 double qx = msg.pose().orientation().qx();
113 double qy = msg.pose().orientation().qy();
114 double qz = msg.pose().orientation().qz();
115 double qw = msg.pose().orientation().qw();
116
117 // apollo::common::math::EulerAnglesZXY<double> euler(
118 // qw, qx, qy, qz);
119 // double roll = euler.roll();
120 // double pitch = euler.pitch();
121 // double yaw = euler.yaw();
122
123 double std_x = msg.uncertainty().position_std_dev().x();
124 double std_y = msg.uncertainty().position_std_dev().y();
125 double std_z = msg.uncertainty().position_std_dev().z();
126
127 fprintf(lidar_loc_file_handle_,
128 "%u %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", index, timestamp,
129 x, y, z, qx, qy, qz, qw, std_x, std_y, std_z);
130
131 ++index;
132}

◆ OdometryLocCallback()

void apollo::localization::msf::LocationExporter::OdometryLocCallback ( const std::string &  msg)

在文件 location_exporter.cc167 行定义.

167 {
168 AINFO << "Odometry location callback.";
169 Gps msg;
170 msg.ParseFromString(msg_string);
171 static unsigned int index = 1;
172
173 double timestamp = msg.header().timestamp_sec();
174 double x = msg.localization().position().x();
175 double y = msg.localization().position().y();
176 double z = msg.localization().position().z();
177
178 double qx = msg.localization().orientation().qx();
179 double qy = msg.localization().orientation().qy();
180 double qz = msg.localization().orientation().qz();
181 double qw = msg.localization().orientation().qw();
182
183 // apollo::common::math::EulerAnglesZXY<double> euler(
184 // qw, qx, qy, qz);
185 // double roll = euler.roll();
186 // double pitch = euler.pitch();
187 // double yaw = euler.yaw();
188
189 double std_x = 0;
190 double std_y = 0;
191 double std_z = 0;
192
193 fprintf(odometry_loc_file_handle_,
194 "%u %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", index, timestamp,
195 x, y, z, qx, qy, qz, qw, std_x, std_y, std_z);
196
197 ++index;
198}

该类的文档由以下文件生成: