Apollo 10.0
自动驾驶开放平台
huace_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 HuaCeBaseParser::PrepareMessageStatus(const uint8_t& system_state,
64 const uint8_t& satellite_status) {
65 switch (system_state) {
66 case 0:
68 break;
69 case 1:
70 case 2:
72 break;
73 default:
75 }
76 switch (satellite_status) {
77 case 0:
79 break;
80 case 1:
81 case 6:
83 break;
84 case 2:
85 case 7:
87 break;
88 case 3:
90 break;
91 case 4:
93 break;
94 case 5:
96 break;
97 case 8:
99 break;
100 case 9:
102 break;
103 default:
105 }
106}
107
108void HuaCeBaseParser::FillGnssBestpos() {
109 bestpos_.set_measurement_time(decode_message_.gps_timestamp_sec);
110 bestpos_.set_sol_status(decode_message_.solution_status);
111 bestpos_.set_sol_type(decode_message_.solution_type);
112 bestpos_.set_latitude(decode_message_.Latitude);
113 bestpos_.set_longitude(decode_message_.Longitude);
114 bestpos_.set_height_msl(decode_message_.Altitude);
115 bestpos_.set_latitude_std_dev(decode_message_.lat_std);
116 bestpos_.set_longitude_std_dev(decode_message_.lon_std);
117 bestpos_.set_height_std_dev(decode_message_.alti_std);
118 bestpos_.set_num_sats_tracked(decode_message_.satellites_num);
119 bestpos_.set_num_sats_in_solution(decode_message_.satellites_num);
120 bestpos_.set_num_sats_l1(decode_message_.satellites_num);
121 bestpos_.set_num_sats_multi(decode_message_.satellites_num);
122}
123
124void HuaCeBaseParser::FillIns() {
125 ins_.mutable_euler_angles()->set_x(decode_message_.Roll * DEG_TO_RAD);
126 ins_.mutable_euler_angles()->set_y(-decode_message_.Pitch * DEG_TO_RAD);
127 ins_.mutable_euler_angles()->set_z(
129 ins_.mutable_position()->set_lon(decode_message_.Longitude);
130 ins_.mutable_position()->set_lat(decode_message_.Latitude);
131 ins_.mutable_position()->set_height(decode_message_.Altitude);
132 ins_.mutable_linear_velocity()->set_x(decode_message_.Ve);
133 ins_.mutable_linear_velocity()->set_y(decode_message_.Vn);
134 ins_.mutable_linear_velocity()->set_z(decode_message_.Vu);
136 ins_.mutable_linear_acceleration());
138 decode_message_.GyroZ, ins_.mutable_angular_velocity());
139 ins_.set_measurement_time(decode_message_.gps_timestamp_sec);
140 ins_.mutable_header()->set_timestamp_sec(cyber::Time::Now().ToSecond());
141
147 ins_.set_type(Ins::GOOD);
148 break;
150 ins_.set_type(Ins::CONVERGING);
151 break;
152 default:
153 ins_.set_type(Ins::INVALID);
154 break;
155 }
156}
157
158void HuaCeBaseParser::FillInsStat() {
159 ins_stat_.set_ins_status(decode_message_.solution_status);
160 ins_stat_.set_pos_type(decode_message_.solution_type);
161}
162
163void HuaCeBaseParser::FillImu() {
165 imu_.mutable_linear_acceleration());
167 decode_message_.GyroZ, imu_.mutable_angular_velocity());
168 imu_.set_measurement_time(decode_message_.gps_timestamp_sec);
169}
170
171void HuaCeBaseParser::FillHeading() {
172 heading_.set_solution_status(decode_message_.solution_status);
173 heading_.set_position_type(decode_message_.solution_type);
174 heading_.set_measurement_time(decode_message_.gps_timestamp_sec);
175 heading_.set_heading(decode_message_.Heading);
176 heading_.set_pitch(decode_message_.Pitch);
177 heading_.set_heading_std_dev(decode_message_.yaw_std);
178 heading_.set_pitch_std_dev(decode_message_.pitch_std);
179 // heading_.set_station_id("0");
180 heading_.set_satellite_number_multi(decode_message_.satellites_num);
181 heading_.set_satellite_soulution_number(decode_message_.satellites_num);
182}
183
184} // namespace gnss
185} // namespace drivers
186} // namespace apollo
static Time Now()
get the current time.
Definition time.cc:57
void PrepareMessageStatus(const uint8_t &system_state, const uint8_t &satellite_status)
virtual void GetMessages(MessageInfoVec *messages)
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