Apollo 10.0
自动驾驶开放平台
broadgnss_base_parser.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 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// An parser for decoding binary messages from a NovAtel receiver. The following
18// messages must be
19// logged in order for this parser to work properly.
20//
22
23#include <cmath>
24#include <iostream>
25#include <limits>
26#include <memory>
27#include <vector>
28
29namespace apollo {
30namespace drivers {
31namespace gnss {
32
34
36 if (data_ == nullptr) {
37 return;
38 }
39 if (!PrepareMessage()) {
40 return;
41 }
42
43 FillGnssBestpos();
44 FillImu();
45 FillHeading();
46 FillIns();
47 FillInsStat();
48
49 if (bestpos_ratecontrol_.check()) {
50 messages->push_back(MessageInfo{MessageType::BEST_GNSS_POS,
51 reinterpret_cast<MessagePtr>(&bestpos_)});
52 }
53 messages->push_back(
54 MessageInfo{MessageType::IMU, reinterpret_cast<MessagePtr>(&imu_)});
55 messages->push_back(MessageInfo{MessageType::HEADING,
56 reinterpret_cast<MessagePtr>(&heading_)});
57 messages->push_back(
58 MessageInfo{MessageType::INS, reinterpret_cast<MessagePtr>(&ins_)});
59 messages->push_back(MessageInfo{MessageType::INS_STAT,
60 reinterpret_cast<MessagePtr>(&ins_stat_)});
61}
62
63void BroadGnssBaseParser::PrepareMessageStatus(const uint8_t& solution_status,
64 const uint8_t& solution_type) {
65 switch (solution_status) {
66 case 0:
68 break;
69 case 1:
70 case 2:
71 case 3:
73 break;
74 case 4:
76 break;
77 default:
79 }
80 switch (solution_type) {
81 case 0:
83 break;
84 case 1:
85 case 2:
86 case 3:
87 case 6:
89 break;
90 case 4:
92 break;
93 case 5:
95 break;
96 default:
98 }
99}
100
101void BroadGnssBaseParser::FillGnssBestpos() {
102 bestpos_.set_measurement_time(broadgnss_message_.gps_timestamp_sec);
103 bestpos_.set_sol_status(broadgnss_message_.solution_status);
104 bestpos_.set_sol_type(broadgnss_message_.solution_type);
105 bestpos_.set_latitude(broadgnss_message_.latitude);
106 bestpos_.set_longitude(broadgnss_message_.longitude);
107 bestpos_.set_height_msl(broadgnss_message_.altitude);
108 bestpos_.set_latitude_std_dev(broadgnss_message_.lat_std);
109 bestpos_.set_longitude_std_dev(broadgnss_message_.lon_std);
110 bestpos_.set_height_std_dev(broadgnss_message_.alti_std);
111 bestpos_.set_num_sats_tracked(broadgnss_message_.satellites_num);
112 bestpos_.set_num_sats_in_solution(broadgnss_message_.satellites_num);
113 bestpos_.set_num_sats_l1(broadgnss_message_.satellites_num);
114 bestpos_.set_num_sats_multi(broadgnss_message_.satellites_num);
115}
116
117void BroadGnssBaseParser::FillIns() {
118 ins_.mutable_euler_angles()->set_x(broadgnss_message_.roll * DEG_TO_RAD);
119 ins_.mutable_euler_angles()->set_y(-broadgnss_message_.pitch * DEG_TO_RAD);
120 ins_.mutable_euler_angles()->set_z(
122 ins_.mutable_position()->set_lon(broadgnss_message_.longitude);
123 ins_.mutable_position()->set_lat(broadgnss_message_.latitude);
124 ins_.mutable_position()->set_height(broadgnss_message_.altitude);
125 ins_.mutable_linear_velocity()->set_x(broadgnss_message_.ve);
126 ins_.mutable_linear_velocity()->set_y(broadgnss_message_.vn);
127 ins_.mutable_linear_velocity()->set_z(broadgnss_message_.vu);
129 broadgnss_message_.acc_z, ins_.mutable_linear_acceleration());
131 broadgnss_message_.gyro_z, ins_.mutable_angular_velocity());
132 ins_.set_measurement_time(broadgnss_message_.gps_timestamp_sec);
133 ins_.mutable_header()->set_timestamp_sec(cyber::Time::Now().ToSecond());
134
140 ins_.set_type(Ins::GOOD);
141 break;
143 ins_.set_type(Ins::CONVERGING);
144 break;
145 default:
146 ins_.set_type(Ins::INVALID);
147 break;
148 }
149}
150
151void BroadGnssBaseParser::FillInsStat() {
152 ins_stat_.set_ins_status(broadgnss_message_.solution_status);
153 ins_stat_.set_pos_type(broadgnss_message_.solution_type);
154}
155
156void BroadGnssBaseParser::FillImu() {
158 broadgnss_message_.acc_z, imu_.mutable_linear_acceleration());
160 broadgnss_message_.gyro_z, imu_.mutable_angular_velocity());
161 imu_.set_measurement_time(broadgnss_message_.gps_timestamp_sec);
162}
163
164void BroadGnssBaseParser::FillHeading() {
165 heading_.set_solution_status(broadgnss_message_.solution_status);
166 heading_.set_position_type(broadgnss_message_.solution_type);
167 heading_.set_measurement_time(broadgnss_message_.gps_timestamp_sec);
168 heading_.set_heading(broadgnss_message_.heading);
169 heading_.set_pitch(broadgnss_message_.pitch);
170 heading_.set_heading_std_dev(broadgnss_message_.yaw_std);
171 heading_.set_pitch_std_dev(broadgnss_message_.pitch_std);
172 // heading_.set_station_id("0");
173 heading_.set_satellite_number_multi(broadgnss_message_.satellites_num);
174 heading_.set_satellite_soulution_number(broadgnss_message_.satellites_num);
175}
176
177} // namespace gnss
178} // namespace drivers
179} // namespace apollo
static Time Now()
get the current time.
Definition time.cc:57
virtual void GetMessages(MessageInfoVec *messages)
void PrepareMessageStatus(const uint8_t &solution_status, const uint8_t &solution_type)
const uint8_t * data_
Definition parser.h:138
::google::protobuf::Message * MessagePtr
Definition parser.h:34
constexpr double DEG_TO_RAD
void rfu_to_flu(double r, double f, double u, ::apollo::common::Point3D *flu)
constexpr double azimuth_deg_to_yaw_rad(double azimuth)
std::vector< MessageInfo > MessageInfoVec
Definition parser.h:57
class register implement
Definition arena_queue.h:37