Apollo 10.0
自动驾驶开放平台
decode_0B.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2024 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
17#include <cmath>
18#include <iostream>
19
22
23typedef struct { /* time struct */
24 time_t time; /* time (s) expressed by standard time_t */
25 double sec; /* fraction of second under 1 s */
26} gtime_t;
27
28gtime_t epoch2time_sdk(const double* ep) {
29 const int doy[] = {1, 32, 60, 91, 121, 152, 182, 213, 244, 274, 305, 335};
30 gtime_t time = {0};
31 int days, sec, year = static_cast<int>(ep[0]), mon = static_cast<int>(ep[1]),
32 day = static_cast<int>(ep[2]);
33
34 if (year < 1970 || 2099 < year || mon < 1 || 12 < mon) return time;
35
36 /* leap year if year%4==0 in 1901-2099 */
37 days = (year - 1970) * 365 + (year - 1969) / 4 + doy[mon - 1] + day - 2 +
38 (year % 4 == 0 && mon >= 3 ? 1 : 0);
39 sec = static_cast<int>(floor(ep[5]));
40 time.time = static_cast<time_t>(days) * 86400 +
41 static_cast<int>(ep[3]) * 3600 + static_cast<int>(ep[4]) * 60 +
42 sec;
43 time.sec = ep[5] - sec;
44 return time;
45}
46
47gtime_t gpst2time_sdk(int week, double sec) {
48 static const double gpst0[] = {1980, 1, 6, 0, 0, 0};
49 gtime_t t = epoch2time_sdk(gpst0);
50
51 if (sec < -1E9 || 1E9 < sec) sec = 0.0;
52 t.time += 86400 * 7 * week + static_cast<int>(sec);
53 t.sec = sec - static_cast<int>(sec);
54 return t;
55}
56
58 filename2 = "BDDB10.csv";
59 content2 =
60 "Lon_deg,LonStd,Lat_deg,LatStd,Alt_m,AltStd,fix,RtkAge_s,Trk_deg,Vspd_"
61 "mps,LatencyVel_s,BaseLineLenth_m,Heading_dg,HeadingStd,Pitch_deg,"
62 "PitchStd,UtcYear,UtcMon,UtcDay,UtcHour,UtcMin,UtcSec,ItowPos,ItowVel,"
63 "ItowHeading,RecMsgOutput,SvNumMst";
64
65 filename0b = "BDDB0B.csv";
66 content0b =
67 "roll,pitch,yaw,GyroX,GyroY,GyroZ,x_acc,y_acc,z_acc,latitude,longitude,"
68 "altitude,north_vel,east_vel,ground_vel,ins_status,modestatus,system_ms";
69
70 // createFileAndWrite(filename2, content2);
71 // createFileAndWrite(filename0b, content0b);
72
75}
76
78
79void Decode_0B::subData(const uint8_t* sub_address, int& index) {
80 std::string type = "";
81 char str[16] = {0};
82 std::snprintf(str, sizeof(str), "%02X%02X%02X", sub_address[0],
83 sub_address[1], sub_address[2]);
84 type += str;
85 if (type == m_typeImu) {
86 parse0B(sub_address, index);
87 } else if (type == m_typeGnss) {
88 parseGnss(sub_address, index);
89 } else {
90 index += 3;
91 printf("protocol type error:%s!\n", type.c_str());
92 }
93}
94
95void Decode_0B::parse0B(const uint8_t* data, int& pos) {
96 static const double deg_coefficient = 360.0 / 32768;
97 static const double degree_to_radians = 6.283185307179586232 / 360.0;
98 static const double angular_coefficient = 300.0 / 32768;
99 static const double acc_coefficient = 12.0 / 32768 * 9.7883105;
100 static const double velocity_coefficient = 100.0 / 32768;
101 static const double deg_to_rad = M_PI / 180.0;
102
103 int sub_index = 3;
104 uint8_t check_sum = 0;
105 int dataLength = getLength(m_typeImu);
106 /* check xor */
107 for (int i = 0; i < dataLength - 1; ++i) {
108 check_sum ^= data[i];
109 }
110
111 if (check_sum == data[dataLength - 1]) {
112 /* roll pitch yaw */
113 float roll = (toValue<int16_t>(data, sub_index)) * deg_coefficient;
114 float pitch = (toValue<int16_t>(data, sub_index)) * deg_coefficient;
115 float x = (toValue<int16_t>(data, sub_index)) * deg_coefficient;
116 if (x > 0) {
117 x = 90.0 - x;
118 } else {
119 x = 90.0 - (360.0 + x);
120 }
121 float yaw = x;
122
123 /* gx gy gz , ax ay az */
124 double imu_msg_y_angular_velocity =
125 (toValue<int16_t>(data, sub_index)) * angular_coefficient;
126 double imu_msg_x_angular_velocity =
127 (toValue<int16_t>(data, sub_index)) * angular_coefficient;
128 double imu_msg_z_angular_velocity =
129 -(toValue<int16_t>(data, sub_index)) * angular_coefficient;
130 double imu_msg_y_acc =
131 (toValue<int16_t>(data, sub_index)) * acc_coefficient;
132 double imu_msg_x_acc =
133 (toValue<int16_t>(data, sub_index)) * acc_coefficient;
134 double imu_msg_z_acc =
135 -(toValue<int16_t>(data, sub_index)) * acc_coefficient;
136
137 double imu_msg_latitude = (toValue<int32_t>(data, sub_index)) * 0.0000001;
138 double imu_msg_longitude = (toValue<int32_t>(data, sub_index)) * 0.0000001;
139 double imu_msg_altitude = (toValue<int32_t>(data, sub_index)) * 0.001;
140
141 float imu_msg_north_velocity =
142 (toValue<int16_t>(data, sub_index)) * velocity_coefficient;
143 float imu_msg_east_velocity =
144 (toValue<int16_t>(data, sub_index)) * velocity_coefficient;
145 float imu_msg_ground_velocity =
146 (toValue<int16_t>(data, sub_index)) * velocity_coefficient;
147 uint8_t imu_msg_ins_status = toValue<uint8_t>(data, sub_index);
148 sub_index = 44;
149 uint8_t modestatus = toValue<uint8_t>(data, sub_index);
150 sub_index = 46;
151 int16_t data1 = toValue<uint16_t>(data, sub_index);
152 int16_t data2 = toValue<uint16_t>(data, sub_index);
153 int16_t data3 = toValue<uint16_t>(data, sub_index);
154
155 sub_index = 52;
156 uint32_t timiddle = toValue<uint32_t>(data, sub_index);
157 double t_ms = timiddle * 2.5 * 0.0001;
158 uint8_t loop_type = toValue<uint8_t>(data, sub_index);
159 sub_index = 58;
160 uint32_t t_week = (toValue<uint32_t>(data, sub_index));
161
162 gtime_t ts_time = gpst2time_sdk(t_week, t_ms - 18);
163
164 int64_t system_ms = (static_cast<double>(ts_time.time) * 1000.0) +
165 (static_cast<double>(ts_time.sec) * 1000.0);
166
167 pos += m_lengthImu;
168
169 // 俯仰角
170 insdata.Pitch_deg = pitch;
171 insdata.Pitch_rad = pitch * degree_to_radians;
172 // 横滚角
173 insdata.Roll_deg = roll;
174 insdata.Roll_rad = roll * degree_to_radians;
175 // 航向角
176 insdata.Yaw_deg = yaw;
177 insdata.Yaw_rad = yaw * degree_to_radians;
178 insdata.GyroX = imu_msg_x_angular_velocity * deg_to_rad; /*gx*/
179 insdata.GyroY = imu_msg_y_angular_velocity * deg_to_rad;
180 insdata.GyroZ = imu_msg_z_angular_velocity * deg_to_rad;
181 insdata.AccX_g = imu_msg_x_acc; /* 零偏修正后加速度计 */
182 insdata.AccY_g = imu_msg_y_acc;
183 insdata.AccZ_g = imu_msg_z_acc;
184
185 // insdata.Lon_deg = imu_msg_longitude;
186 // insdata.Lat_deg = imu_msg_latitude;/*融合后Latitude (deg)*/
187 // insdata.Alt_m = imu_msg_altitude;/*融合后Altitude (m)*/
188
190 imu_msg_north_velocity; /*融合后 NED north velocity (m/s) */
192 imu_msg_east_velocity; /*融合后 NED east velocity (m/s) */
194 imu_msg_ground_velocity; /*融合后 NED down velocity (m/s) */
195 insdata.InsStatus = imu_msg_ins_status;
196 insdata.LoopType = loop_type;
197 insdata.data1 = data1;
198 insdata.data2 = data2;
199 insdata.data3 = data3;
200 insdata.ModeStatus = modestatus;
201 insdata.SysTime_ms = system_ms;
202
203 // Do not write csv.
204 // std::vector<std::string> data_w;
205 // data_w.push_back(std::to_string(pitch));
206 // data_w.push_back(std::to_string(roll));
207 // data_w.push_back(std::to_string(yaw));
208 // data_w.push_back(std::to_string(imu_msg_x_angular_velocity));
209 // data_w.push_back(std::to_string(imu_msg_y_angular_velocity));
210 // data_w.push_back(std::to_string(imu_msg_z_angular_velocity));
211 // data_w.push_back(std::to_string(imu_msg_x_acc));
212 // data_w.push_back(std::to_string(imu_msg_y_acc));
213 // data_w.push_back(std::to_string(imu_msg_z_acc));
214 // data_w.push_back(std::to_string(imu_msg_longitude));
215 // data_w.push_back(std::to_string(imu_msg_latitude));
216 // data_w.push_back(std::to_string(imu_msg_altitude));
217 // data_w.push_back(std::to_string(imu_msg_north_velocity));
218 // data_w.push_back(std::to_string(imu_msg_east_velocity));
219 // data_w.push_back(std::to_string(imu_msg_ground_velocity));
220 // data_w.push_back(std::to_string(imu_msg_ins_status));
221 // data_w.push_back(std::to_string(modestatus));
222 // data_w.push_back(std::to_string(system_ms));
223
224 // if (AppendCsv(filename0b, data_w)) {
225 // // std::cout << "数据成功写入到文件 " << filename << "\n";
226 // } else {
227 // std::cerr << "写入文件时出现错误\n";
228 // }
229
230 update_ins = 1;
231 } else {
232 pos += 3;
233 }
234}
235
236void Decode_0B::parseGnss(const uint8_t* data, int& pos) {
237 int sub_index = 3;
238 uint8_t check_sum = 0;
239 int dataLength = getLength(m_typeGnss);
240 /* check xor */
241 for (int i = 0; i < dataLength - 1; ++i) {
242 check_sum ^= data[i];
243 }
244
245 if (check_sum == data[dataLength - 1]) {
246 double m_gnssMsg_longitude =
247 (toValue<int32_t>(data, sub_index)) * 0.0000001;
248 double m_gnssMsg_lon_sigma = (toValue<int16_t>(data, sub_index)) * 0.001;
249 double m_gnssMsg_latitude = (toValue<int32_t>(data, sub_index)) * 0.0000001;
250 double m_gnssMsg_lat_sigma = (toValue<int16_t>(data, sub_index)) * 0.001;
251 double m_gnssMsg_altitude = (toValue<int32_t>(data, sub_index)) * 0.001;
252 double m_gnssMsg_alt_sigma = (toValue<int16_t>(data, sub_index)) * 0.001;
253
254 double m_gnssMsg_gps_fix = toValue<uint16_t>(data, sub_index);
255 float m_gnssMsg_rtk_age = toValue<uint16_t>(data, sub_index);
256 uint8_t m_gnssMsg_flags_pos = data[sub_index++];
257 uint8_t m_gnssMsg_flags_vel = data[sub_index++];
258 uint8_t m_gnssMsg_flags_attitude = data[sub_index++];
259 uint8_t m_gnssMsg_flags_time = data[sub_index++];
260
261 double m_gnssMsg_hor_vel = (toValue<int16_t>(data, sub_index)) * 0.01;
262 double m_gnssMsg_track_angle = (toValue<int16_t>(data, sub_index)) * 0.01;
263 double m_gnssMsg_ver_vel = (toValue<int16_t>(data, sub_index)) * 0.01;
264 double m_gnssMsg_latency_vel = (toValue<int16_t>(data, sub_index)) * 0.001;
265 double m_gnssMsg_base_length = (toValue<int16_t>(data, sub_index)) * 0.001;
266
267 double m_gnssMsg_yaw = (toValue<int16_t>(data, sub_index)) * 0.01;
268 double m_gnssMsg_yaw_sigma = (toValue<int16_t>(data, sub_index)) * 0.001;
269 double m_gnssMsg_pitch = (toValue<int16_t>(data, sub_index)) * 0.001;
270 double m_gnssMsg_pitch_sigma = (toValue<int16_t>(data, sub_index)) * 0.001;
271
272 uint16_t utc_year_m = toValue<uint16_t>(data, sub_index);
273 uint16_t utc_year = (utc_year_m & 0x3f) + 2000;
274 // week_year = (((utc_year_m >> 6)&0x3ff) +2000);
275 uint8_t utc_mon = data[sub_index++];
276 uint8_t utc_day = data[sub_index++];
277 uint8_t utc_hour = data[sub_index++];
278 uint8_t utc_min = data[sub_index++];
279 float utc_sec = toValue<uint16_t>(data, sub_index) * 0.001;
280
281 double m_gnssMsg_ts_pos = toValue<uint32_t>(data, sub_index);
282 double m_gnssMsg_ts_vel = toValue<uint32_t>(data, sub_index);
283 double m_gnssMsg_ts_heading = toValue<uint32_t>(data, sub_index);
284 double m_gnssMsg_state = data[sub_index++];
285 double m_gnssMsg_num_master = data[sub_index++];
286 sub_index++;
287
288 double m_gnssMsg_gdop = (toValue<int16_t>(data, sub_index)) * 0.01;
289 double m_gnssMsg_pdop = (toValue<int16_t>(data, sub_index)) * 0.01;
290 double m_gnssMsg_hdop = (toValue<int16_t>(data, sub_index)) * 0.01;
291 double m_gnssMsg_htdop = (toValue<int16_t>(data, sub_index)) * 0.01;
292 double m_gnssMsg_tdop = (toValue<int16_t>(data, sub_index)) * 0.01;
293 double m_gnssMsg_num_reserve = data[sub_index++];
294
295 pos += m_lengthGnss;
296
297 insdata.flag_pos = m_gnssMsg_flags_pos;
298 insdata.Lon_deg = m_gnssMsg_longitude;
299 insdata.Lat_deg = m_gnssMsg_latitude; /*融合后Latitude (deg)*/
300 insdata.Alt_m = m_gnssMsg_altitude; /*融合后Altitude (m)*/
301 insdata.differential_age = m_gnssMsg_rtk_age;
302
303 // Do not write csv.
304 // std::vector<std::string> data_w;
305 // data_w.push_back(std::to_string(m_gnssMsg_longitude));
306 // data_w.push_back(std::to_string(m_gnssMsg_lon_sigma));
307 // data_w.push_back(std::to_string(m_gnssMsg_latitude));
308 // data_w.push_back(std::to_string(m_gnssMsg_lat_sigma));
309 // data_w.push_back(std::to_string(m_gnssMsg_altitude));
310 // data_w.push_back(std::to_string(m_gnssMsg_alt_sigma));
311 // data_w.push_back(std::to_string(m_gnssMsg_gps_fix));
312 // data_w.push_back(std::to_string(m_gnssMsg_rtk_age));
313 // // data_w.push_back(std::to_string(m_gnssMsg_msg_type));
314 // // data_w.push_back(std::to_string(m_gnssMsg_flags_pos));
315 // // data_w.push_back(std::to_string(m_gnssMsg_flags_vel));
316 // // data_w.push_back(std::to_string(m_gnssMsg_flags_attitude));
317 // // data_w.push_back(std::to_string(m_gnssMsg_flags_time));
318 // // data_w.push_back(std::to_string(m_gnssMsg_hor_vel));
319 // data_w.push_back(std::to_string(m_gnssMsg_track_angle));
320 // data_w.push_back(std::to_string(m_gnssMsg_ver_vel));
321 // data_w.push_back(std::to_string(m_gnssMsg_latency_vel));
322 // data_w.push_back(std::to_string(m_gnssMsg_base_length));
323 // data_w.push_back(std::to_string(m_gnssMsg_yaw));
324 // data_w.push_back(std::to_string(m_gnssMsg_yaw_sigma));
325 // data_w.push_back(std::to_string(m_gnssMsg_pitch));
326 // data_w.push_back(std::to_string(m_gnssMsg_pitch_sigma));
327 // data_w.push_back(std::to_string(utc_year));
328 // data_w.push_back(std::to_string(utc_mon));
329 // data_w.push_back(std::to_string(utc_day));
330 // data_w.push_back(std::to_string(utc_hour));
331 // data_w.push_back(std::to_string(utc_min));
332 // data_w.push_back(std::to_string(utc_sec));
333 // data_w.push_back(std::to_string(m_gnssMsg_ts_pos));
334 // data_w.push_back(std::to_string(m_gnssMsg_ts_vel));
335 // data_w.push_back(std::to_string(m_gnssMsg_ts_heading));
336 // data_w.push_back(std::to_string(m_gnssMsg_state));
337 // data_w.push_back(std::to_string(m_gnssMsg_num_master));
338 // data_w.push_back(std::to_string(m_gnssMsg_gdop));
339 // data_w.push_back(std::to_string(m_gnssMsg_pdop));
340 // data_w.push_back(std::to_string(m_gnssMsg_hdop));
341 // // data_w.push_back(std::to_string(m_gnssMsg_vdop));
342 // data_w.push_back(std::to_string(m_gnssMsg_tdop));
343 // data_w.push_back(std::to_string(m_gnssMsg_num_reserve));
344
345 // if (AppendCsv(filename2, data_w)) {
346 // // std::cout << "数据成功写入到文件 " << filename << "\n";
347 // } else {
348 // std::cerr << "写入文件时出现错误\n";
349 // }
350
351 } else {
352 pos += 3;
353 }
354}
std::string m_typeGnss
void parseGnss(const uint8_t *data, int &pos)
Definition decode_0B.cc:236
virtual ~Decode_0B()
Definition decode_0B.cc:77
std::string m_typeImu
void parse0B(const uint8_t *data, int &pos)
Definition decode_0B.cc:95
void subData(const uint8_t *sub_address, int &index)
Definition decode_0B.cc:79
bool registProtocol(const std::string &protocolFlag, int length, ProtocolAsensing *sub)
int getLength(const std::string &flag)
gtime_t epoch2time_sdk(const double *ep)
Definition decode_0B.cc:28
gtime_t gpst2time_sdk(int week, double sec)
Definition decode_0B.cc:47
uint8_t InsStatus
float differential_age
uint8_t flag_pos
uint8_t LoopType
uint8_t ModeStatus
int64_t SysTime_ms
double sec
Definition decode_0B.cc:25
time_t time
Definition decode_0B.cc:24