23#include "Eigen/Geometry"
24#include "boost/array.hpp"
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"
41using ::apollo::localization::CorrectedImu;
42using ::apollo::localization::Gps;
48constexpr double DEG_TO_RAD_LOCAL = M_PI / 180.0;
49const char *WGS84_TEXT =
"+proj=latlong +ellps=WGS84";
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};
59 const std::shared_ptr<apollo::cyber::Node> &node)
60 : config_(config), tf_broadcaster_(node), node_(node) {
61 std::string utm_target_param;
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);
73 ins_status_.mutable_header()->set_timestamp_sec(
75 gnss_status_.mutable_header()->set_timestamp_sec(
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_ =
86 epochobservation_writer_ =
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);
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_);
100 AFATAL <<
"Failed to create data parser.";
110 AERROR <<
"Data parser not init.";
114 data_parser_->Update(msg);
116 data_parser_->GetMessages(&messages);
117 for (
auto &message : messages) {
118 DispatchMessage(message);
125 if (ins_status_record_ !=
static_cast<uint32_t
>(ins->
type()) ||
126 (now - last_notify) > 1.0) {
128 ins_status_record_ =
static_cast<uint32_t
>(ins->
type());
129 switch (ins->
type()) {
144 common::util::FillHeader(
"gnss", &ins_status_);
145 insstatus_writer_->Write(ins_status_);
150 gnss_status_.set_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()));
156 gnss_status_.set_solution_completed(
true);
158 gnss_status_.set_solution_completed(
false);
160 common::util::FillHeader(
"gnss", &gnss_status_);
161 gnssstatus_writer_->Write(gnss_status_);
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));
172 PublishBestpos(message);
180 CheckInsStatus(As<::apollo::drivers::gnss::Ins>(message));
181 PublishCorrimu(message);
182 PublishOdometry(message);
185 if (!has_ins_stat_message_) {
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);
198 PublishInsStat(message);
199 has_ins_stat_message_ =
true;
205 PublishEphemeris(message);
209 PublishObservation(message);
213 PublishHeading(message);
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);
227void DataParser::PublishBestpos(
const MessagePtr message) {
228 auto bestpos = std::make_shared<GnssBestPose>(*As<GnssBestPose>(message));
229 common::util::FillHeader(
"gnss", bestpos.get());
232 }
else if (bestpos->has_measurement_time()) {
233 bestpos->set_measurement_time(
236 gnssbestpose_writer_->Write(bestpos);
239void DataParser::PublishImu(
const MessagePtr message) {
240 auto raw_imu = std::make_shared<Imu>(*As<Imu>(message));
241 Imu *imu = As<Imu>(message);
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());
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());
252 common::util::FillHeader(
"gnss", raw_imu.get());
255 }
else if (raw_imu->has_measurement_time()) {
256 raw_imu->set_measurement_time(
259 rawimu_writer_->Write(raw_imu);
262void DataParser::PublishOdometry(
const MessagePtr message) {
263 Ins *ins = As<Ins>(message);
264 auto gps = std::make_shared<Gps>();
266 common::util::FillHeader(
"gnss", gps.get());
268 gps->mutable_header()->set_timestamp_sec(
271 auto *gps_msg = gps->mutable_localization();
274 double x = ins->position().lon();
275 double y = ins->position().lat();
276 x *= DEG_TO_RAD_LOCAL;
277 y *= DEG_TO_RAD_LOCAL;
279 pj_transform(wgs84pj_source_, utm_target_, 1, 1, &x, &y, NULL);
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());
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());
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());
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());
301 gps_writer_->Write(gps);
303 TransformStamped transform;
304 GpsToTransformStamped(gps, &transform);
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());
314 imu->mutable_header()->set_timestamp_sec(
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());
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());
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);
332 corrimu_writer_->Write(imu);
335void DataParser::PublishEphemeris(
const MessagePtr message) {
336 auto eph = std::make_shared<GnssEphemeris>(*As<GnssEphemeris>(message));
337 gnssephemeris_writer_->Write(eph);
340void DataParser::PublishObservation(
const MessagePtr message) {
342 std::make_shared<EpochObservation>(*As<EpochObservation>(message));
343 epochobservation_writer_->Write(observation);
346void DataParser::PublishHeading(
const MessagePtr message) {
347 auto heading = std::make_shared<Heading>(*As<Heading>(message));
350 }
else if (heading->has_measurement_time()) {
351 heading->set_measurement_time(
354 heading_writer_->Write(heading);
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());
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());
Cyber has builtin time type Time.
static Time Now()
get the current time.
double ToSecond() const
convert time to second.
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)
Some string util functions.
::google::protobuf::Message * MessagePtr
std::vector< MessageInfo > MessageInfoVec
T gps2unix(const T gps_seconds)
optional uint32 solution_status
optional uint32 position_type
optional string proj4_text
optional bool use_gnss_time
optional string child_frame_id