Apollo 10.0
自动驾驶开放平台
data_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
18
19#include <cmath>
20#include <memory>
21#include <string>
22
23#include "Eigen/Geometry"
24#include "boost/array.hpp"
25
26#include "modules/common_msgs/localization_msgs/imu.pb.h"
27#include "modules/common_msgs/sensor_msgs/gnss_best_pose.pb.h"
28#include "modules/common_msgs/sensor_msgs/gnss_raw_observation.pb.h"
29#include "modules/common_msgs/sensor_msgs/heading.pb.h"
30
31#include "cyber/cyber.h"
36
37namespace apollo {
38namespace drivers {
39namespace gnss {
40
41using ::apollo::localization::CorrectedImu;
42using ::apollo::localization::Gps;
43
45
46namespace {
47
48constexpr double DEG_TO_RAD_LOCAL = M_PI / 180.0;
49const char *WGS84_TEXT = "+proj=latlong +ellps=WGS84";
50
51// covariance data for pose if can not get from novatel inscov topic
52static const boost::array<double, 36> POSE_COVAR = {
53 2, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0,
54 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0.01};
55
56} // namespace
57
59 const std::shared_ptr<apollo::cyber::Node> &node)
60 : config_(config), tf_broadcaster_(node), node_(node) {
61 std::string utm_target_param;
62
63 wgs84pj_source_ = pj_init_plus(WGS84_TEXT);
64 utm_target_ = pj_init_plus(config_.proj4_text().c_str());
65 gnss_status_.set_solution_status(0);
66 gnss_status_.set_num_sats(0);
67 gnss_status_.set_position_type(0);
68 gnss_status_.set_solution_completed(false);
69 ins_status_.set_type(InsStatus::INVALID);
70}
71
73 ins_status_.mutable_header()->set_timestamp_sec(
74 cyber::Time::Now().ToSecond());
75 gnss_status_.mutable_header()->set_timestamp_sec(
76 cyber::Time::Now().ToSecond());
77
78 gnssstatus_writer_ = node_->CreateWriter<GnssStatus>(FLAGS_gnss_status_topic);
79 insstatus_writer_ = node_->CreateWriter<InsStatus>(FLAGS_ins_status_topic);
80 gnssbestpose_writer_ =
81 node_->CreateWriter<GnssBestPose>(FLAGS_gnss_best_pose_topic);
82 corrimu_writer_ = node_->CreateWriter<CorrectedImu>(FLAGS_imu_topic);
83 insstat_writer_ = node_->CreateWriter<InsStat>(FLAGS_ins_stat_topic);
84 gnssephemeris_writer_ =
85 node_->CreateWriter<GnssEphemeris>(FLAGS_gnss_rtk_eph_topic);
86 epochobservation_writer_ =
87 node_->CreateWriter<EpochObservation>(FLAGS_gnss_rtk_obs_topic);
88 heading_writer_ = node_->CreateWriter<Heading>(FLAGS_heading_topic);
89 rawimu_writer_ = node_->CreateWriter<Imu>(FLAGS_raw_imu_topic);
90 gps_writer_ = node_->CreateWriter<Gps>(FLAGS_gps_topic);
91
92 common::util::FillHeader("gnss", &ins_status_);
93 insstatus_writer_->Write(ins_status_);
94 common::util::FillHeader("gnss", &gnss_status_);
95 gnssstatus_writer_->Write(gnss_status_);
96
97 AINFO << "Creating data parser of format: " << config_.data().format();
98 data_parser_.reset(Parser::CreateParser(config_));
99 if (!data_parser_) {
100 AFATAL << "Failed to create data parser.";
101 return false;
102 }
103
104 init_flag_ = true;
105 return true;
106}
107
108void DataParser::ParseRawData(const std::string &msg) {
109 if (!init_flag_) {
110 AERROR << "Data parser not init.";
111 return;
112 }
113
114 data_parser_->Update(msg);
115 MessageInfoVec messages;
116 data_parser_->GetMessages(&messages);
117 for (auto &message : messages) {
118 DispatchMessage(message);
119 }
120}
121
122void DataParser::CheckInsStatus(::apollo::drivers::gnss::Ins *ins) {
123 static double last_notify = cyber::Time().Now().ToSecond();
124 double now = cyber::Time().Now().ToSecond();
125 if (ins_status_record_ != static_cast<uint32_t>(ins->type()) ||
126 (now - last_notify) > 1.0) {
127 last_notify = now;
128 ins_status_record_ = static_cast<uint32_t>(ins->type());
129 switch (ins->type()) {
131 ins_status_.set_type(apollo::drivers::gnss::InsStatus::GOOD);
132 break;
133
136 break;
137
139 default:
140 ins_status_.set_type(apollo::drivers::gnss::InsStatus::INVALID);
141 break;
142 }
143
144 common::util::FillHeader("gnss", &ins_status_);
145 insstatus_writer_->Write(ins_status_);
146 }
147}
148
149void DataParser::CheckGnssStatus(::apollo::drivers::gnss::Gnss *gnss) {
150 gnss_status_.set_solution_status(
151 static_cast<uint32_t>(gnss->solution_status()));
152 gnss_status_.set_num_sats(static_cast<uint32_t>(gnss->num_sats()));
153 gnss_status_.set_position_type(static_cast<uint32_t>(gnss->position_type()));
154
155 if (static_cast<uint32_t>(gnss->solution_status()) == 0) {
156 gnss_status_.set_solution_completed(true);
157 } else {
158 gnss_status_.set_solution_completed(false);
159 }
160 common::util::FillHeader("gnss", &gnss_status_);
161 gnssstatus_writer_->Write(gnss_status_);
162}
163
164void DataParser::DispatchMessage(const MessageInfo &message_info) {
165 auto &message = message_info.message_ptr;
166 switch (message_info.type) {
168 CheckGnssStatus(As<::apollo::drivers::gnss::Gnss>(message));
169 break;
170
172 PublishBestpos(message);
173 break;
174
175 case MessageType::IMU:
176 PublishImu(message);
177 break;
178
179 case MessageType::INS:
180 CheckInsStatus(As<::apollo::drivers::gnss::Ins>(message));
181 PublishCorrimu(message);
182 PublishOdometry(message);
183
184 // if not has ins_stat message, publish ins_stat from best pose
185 if (!has_ins_stat_message_) {
186 MessagePtr msg_ptr;
187 if (data_parser_->GetInsStat(&msg_ptr)) {
188 auto ins_stat = std::make_shared<InsStat>(*As<InsStat>(msg_ptr));
189 if (ins_stat->has_ins_status()) {
190 common::util::FillHeader("gnss", ins_stat.get());
191 insstat_writer_->Write(ins_stat);
192 }
193 }
194 }
195 break;
196
198 PublishInsStat(message);
199 has_ins_stat_message_ = true;
200 break;
201
205 PublishEphemeris(message);
206 break;
207
209 PublishObservation(message);
210 break;
211
213 PublishHeading(message);
214 break;
215
216 default:
217 break;
218 }
219}
220
221void DataParser::PublishInsStat(const MessagePtr message) {
222 auto ins_stat = std::make_shared<InsStat>(*As<InsStat>(message));
223 common::util::FillHeader("gnss", ins_stat.get());
224 insstat_writer_->Write(ins_stat);
225}
226
227void DataParser::PublishBestpos(const MessagePtr message) {
228 auto bestpos = std::make_shared<GnssBestPose>(*As<GnssBestPose>(message));
229 common::util::FillHeader("gnss", bestpos.get());
230 if (!config_.use_gnss_time()) {
231 bestpos->set_measurement_time(cyber::Time::Now().ToSecond());
232 } else if (bestpos->has_measurement_time()) {
233 bestpos->set_measurement_time(
234 apollo::drivers::util::gps2unix(bestpos->measurement_time()));
235 }
236 gnssbestpose_writer_->Write(bestpos);
237}
238
239void DataParser::PublishImu(const MessagePtr message) {
240 auto raw_imu = std::make_shared<Imu>(*As<Imu>(message));
241 Imu *imu = As<Imu>(message);
242
243 raw_imu->mutable_linear_acceleration()->set_x(
244 -imu->linear_acceleration().y());
245 raw_imu->mutable_linear_acceleration()->set_y(imu->linear_acceleration().x());
246 raw_imu->mutable_linear_acceleration()->set_z(imu->linear_acceleration().z());
247
248 raw_imu->mutable_angular_velocity()->set_x(-imu->angular_velocity().y());
249 raw_imu->mutable_angular_velocity()->set_y(imu->angular_velocity().x());
250 raw_imu->mutable_angular_velocity()->set_z(imu->angular_velocity().z());
251
252 common::util::FillHeader("gnss", raw_imu.get());
253 if (!config_.use_gnss_time()) {
254 raw_imu->set_measurement_time(cyber::Time::Now().ToSecond());
255 } else if (raw_imu->has_measurement_time()) {
256 raw_imu->set_measurement_time(
257 apollo::drivers::util::gps2unix(raw_imu->measurement_time()));
258 }
259 rawimu_writer_->Write(raw_imu);
260}
261
262void DataParser::PublishOdometry(const MessagePtr message) {
263 Ins *ins = As<Ins>(message);
264 auto gps = std::make_shared<Gps>();
265
266 common::util::FillHeader("gnss", gps.get());
267 if (config_.use_gnss_time()) {
268 gps->mutable_header()->set_timestamp_sec(
269 apollo::drivers::util::gps2unix(ins->measurement_time()));
270 }
271 auto *gps_msg = gps->mutable_localization();
272
273 // 1. pose xyz
274 double x = ins->position().lon();
275 double y = ins->position().lat();
276 x *= DEG_TO_RAD_LOCAL;
277 y *= DEG_TO_RAD_LOCAL;
278
279 pj_transform(wgs84pj_source_, utm_target_, 1, 1, &x, &y, NULL);
280
281 gps_msg->mutable_position()->set_x(x);
282 gps_msg->mutable_position()->set_y(y);
283 gps_msg->mutable_position()->set_z(ins->position().height());
284
285 // 2. orientation
286 Eigen::Quaterniond q =
287 Eigen::AngleAxisd(ins->euler_angles().z() - 90 * DEG_TO_RAD_LOCAL,
288 Eigen::Vector3d::UnitZ()) *
289 Eigen::AngleAxisd(-ins->euler_angles().y(), Eigen::Vector3d::UnitX()) *
290 Eigen::AngleAxisd(ins->euler_angles().x(), Eigen::Vector3d::UnitY());
291
292 gps_msg->mutable_orientation()->set_qx(q.x());
293 gps_msg->mutable_orientation()->set_qy(q.y());
294 gps_msg->mutable_orientation()->set_qz(q.z());
295 gps_msg->mutable_orientation()->set_qw(q.w());
296
297 gps_msg->mutable_linear_velocity()->set_x(ins->linear_velocity().x());
298 gps_msg->mutable_linear_velocity()->set_y(ins->linear_velocity().y());
299 gps_msg->mutable_linear_velocity()->set_z(ins->linear_velocity().z());
300
301 gps_writer_->Write(gps);
302 if (config_.tf().enable()) {
303 TransformStamped transform;
304 GpsToTransformStamped(gps, &transform);
305 tf_broadcaster_.SendTransform(transform);
306 }
307}
308
309void DataParser::PublishCorrimu(const MessagePtr message) {
310 Ins *ins = As<Ins>(message);
311 auto imu = std::make_shared<CorrectedImu>();
312 common::util::FillHeader("gnss", imu.get());
313 if (config_.use_gnss_time()) {
314 imu->mutable_header()->set_timestamp_sec(
315 apollo::drivers::util::gps2unix(ins->measurement_time()));
316 }
317 auto *imu_msg = imu->mutable_imu();
318 imu_msg->mutable_linear_acceleration()->set_x(
319 -ins->linear_acceleration().y());
320 imu_msg->mutable_linear_acceleration()->set_y(ins->linear_acceleration().x());
321 imu_msg->mutable_linear_acceleration()->set_z(ins->linear_acceleration().z());
322
323 imu_msg->mutable_angular_velocity()->set_x(-ins->angular_velocity().y());
324 imu_msg->mutable_angular_velocity()->set_y(ins->angular_velocity().x());
325 imu_msg->mutable_angular_velocity()->set_z(ins->angular_velocity().z());
326
327 imu_msg->mutable_euler_angles()->set_x(ins->euler_angles().x());
328 imu_msg->mutable_euler_angles()->set_y(-ins->euler_angles().y());
329 imu_msg->mutable_euler_angles()->set_z(ins->euler_angles().z() -
330 90 * DEG_TO_RAD_LOCAL);
331
332 corrimu_writer_->Write(imu);
333}
334
335void DataParser::PublishEphemeris(const MessagePtr message) {
336 auto eph = std::make_shared<GnssEphemeris>(*As<GnssEphemeris>(message));
337 gnssephemeris_writer_->Write(eph);
338}
339
340void DataParser::PublishObservation(const MessagePtr message) {
341 auto observation =
342 std::make_shared<EpochObservation>(*As<EpochObservation>(message));
343 epochobservation_writer_->Write(observation);
344}
345
346void DataParser::PublishHeading(const MessagePtr message) {
347 auto heading = std::make_shared<Heading>(*As<Heading>(message));
348 if (!config_.use_gnss_time()) {
349 heading->set_measurement_time(cyber::Time::Now().ToSecond());
350 } else if (heading->has_measurement_time()) {
351 heading->set_measurement_time(
352 apollo::drivers::util::gps2unix(heading->measurement_time()));
353 }
354 heading_writer_->Write(heading);
355}
356
357void DataParser::GpsToTransformStamped(const std::shared_ptr<Gps> &gps,
358 TransformStamped *transform) {
359 transform->mutable_header()->set_timestamp_sec(gps->header().timestamp_sec());
360 transform->mutable_header()->set_frame_id(config_.tf().frame_id());
361 transform->set_child_frame_id(config_.tf().child_frame_id());
362 auto translation = transform->mutable_transform()->mutable_translation();
363 translation->set_x(gps->localization().position().x());
364 translation->set_y(gps->localization().position().y());
365 translation->set_z(gps->localization().position().z());
366 auto rotation = transform->mutable_transform()->mutable_rotation();
367 rotation->set_qx(gps->localization().orientation().qx());
368 rotation->set_qy(gps->localization().orientation().qy());
369 rotation->set_qz(gps->localization().orientation().qz());
370 rotation->set_qw(gps->localization().orientation().qw());
371}
372
373} // namespace gnss
374} // namespace drivers
375} // namespace apollo
Cyber has builtin time type Time.
Definition time.h:31
static Time Now()
get the current time.
Definition time.cc:57
double ToSecond() const
convert time to second.
Definition time.cc:77
void ParseRawData(const std::string &msg)
DataParser(const config::Config &config, const std::shared_ptr< apollo::cyber::Node > &node)
static Parser * CreateParser(const config::Config &config)
Definition parser.h:88
void SendTransform(const TransformStamped &transform)
Send a TransformStamped message The stamped data structure includes frame_id, and time,...
#define AERROR
Definition log.h:44
#define AFATAL
Definition log.h:45
#define AINFO
Definition log.h:42
Some string util functions.
::google::protobuf::Message * MessagePtr
Definition parser.h:34
std::vector< MessageInfo > MessageInfoVec
Definition parser.h:57
T gps2unix(const T gps_seconds)
class register implement
Definition arena_queue.h:37
optional uint32 solution_status
Definition gnss.proto:53
optional uint32 position_type
Definition gnss.proto:54
optional int32 num_sats
Definition gnss.proto:34