47 const std::shared_ptr<apollo::cyber::Node> &node);
53 void DispatchMessage(
const MessageInfo &message_info);
55 void PublishOdometry(
const MessagePtr message);
59 void PublishEphemeris(
const MessagePtr message);
60 void PublishObservation(
const MessagePtr message);
62 void CheckInsStatus(
Ins *ins);
63 void CheckGnssStatus(
Gnss *gnss);
64 void GpsToTransformStamped(
65 const std::shared_ptr<apollo::localization::Gps> &gps,
68 bool init_flag_ =
false;
70 std::unique_ptr<Parser> data_parser_;
75 uint32_t ins_status_record_ =
static_cast<uint32_t
>(0);
76 projPJ wgs84pj_source_;
78 bool has_ins_stat_message_ =
false;
80 std::shared_ptr<apollo::cyber::Node> node_ =
nullptr;
81 std::shared_ptr<apollo::cyber::Writer<GnssStatus>> gnssstatus_writer_ =
83 std::shared_ptr<apollo::cyber::Writer<InsStatus>> insstatus_writer_ =
nullptr;
84 std::shared_ptr<apollo::cyber::Writer<GnssBestPose>> gnssbestpose_writer_ =
86 std::shared_ptr<apollo::cyber::Writer<apollo::localization::CorrectedImu>>
87 corrimu_writer_ =
nullptr;
88 std::shared_ptr<apollo::cyber::Writer<Imu>> rawimu_writer_ =
nullptr;
89 std::shared_ptr<apollo::cyber::Writer<apollo::localization::Gps>>
90 gps_writer_ =
nullptr;
91 std::shared_ptr<apollo::cyber::Writer<InsStat>> insstat_writer_ =
nullptr;
92 std::shared_ptr<apollo::cyber::Writer<GnssEphemeris>> gnssephemeris_writer_ =
94 std::shared_ptr<apollo::cyber::Writer<EpochObservation>>
95 epochobservation_writer_ =
nullptr;
96 std::shared_ptr<apollo::cyber::Writer<Heading>> heading_writer_ =
nullptr;