47 bool Proc(
const std::shared_ptr<localization::Gps> &odometry_msg)
override;
53 void LidarCallback(
const std::shared_ptr<drivers::PointCloud> &lidar_msg);
54 void OdometryStatusCallback(
55 const std::shared_ptr<drivers::gnss::InsStat> &status_msg);
60 void PublishLocalizationStatusTopic(
64 std::shared_ptr<cyber::Reader<drivers::PointCloud>> lidar_listener_ =
nullptr;
66 std::shared_ptr<cyber::Reader<drivers::gnss::InsStat>>
67 odometry_status_listener_ =
nullptr;
69 std::shared_ptr<cyber::Writer<LocalizationEstimate>> localization_talker_ =
72 std::shared_ptr<cyber::Writer<LocalizationEstimate>> lidar_pose_talker_ =
75 std::shared_ptr<cyber::Writer<LocalizationStatus>>
76 localization_status_talker_ =
nullptr;
78 std::string lidar_topic_ =
"";
79 std::string odometry_topic_ =
"";
80 std::string localization_topic_ =
"";
81 std::string lidar_pose_topic_ =
"";
82 std::string odometry_status_topic_ =
"";
83 std::string localization_status_topic_ =
"";
85 std::string broadcast_tf_frame_id_ =
"";
86 std::string broadcast_tf_child_frame_id_ =
"";
87 std::unique_ptr<apollo::transform::TransformBroadcaster> tf2_broadcaster_;
89 std::unique_ptr<NDTLocalization> localization_;