60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
67 void OnPointCloud(
const std::shared_ptr<drivers::PointCloud> &message);
68 void OnRawImu(
const std::shared_ptr<drivers::gnss::Imu> &imu_msg);
69 void OnRawImuCache(
const std::shared_ptr<drivers::gnss::Imu> &imu_msg);
71 const std::shared_ptr<drivers::gnss::EpochObservation> &raw_obs_msg);
73 const std::shared_ptr<drivers::gnss::GnssEphemeris> &gnss_orbit_msg);
75 const std::shared_ptr<drivers::gnss::GnssBestPose> &bestgnsspos_msg);
77 const std::shared_ptr<drivers::gnss::Heading> &gnss_heading_msg);
79 void SetPublisher(
const std::shared_ptr<LocalizationMsgPublisher> &publisher);
83 bool LoadGnssAntennaExtrinsic(
const std::string &file_path,
double *offset_x,
84 double *offset_y,
double *offset_z,
85 double *uncertainty_x,
double *uncertainty_y,
86 double *uncertainty_z);
87 bool LoadImuVehicleExtrinsic(
const std::string &file_path,
double *quat_qx,
88 double *quat_qy,
double *quat_qz,
89 double *quat_qw, Eigen::Vector3d *translation);
90 bool LoadZoneIdFromFolder(
const std::string &folder_path,
int *zone_id);
98 uint64_t pcd_msg_index_;
103 Eigen::Quaternion<double> imu_vehicle_quat_;
104 Eigen::Vector3d imu_vehicle_translation_;
106 std::shared_ptr<LocalizationMsgPublisher> publisher_;
107 std::shared_ptr<drivers::gnss::Imu> raw_imu_msg_;
108 std::mutex mutex_imu_msg_;
109 std::unique_ptr<cyber::Timer> localization_timer_ =
nullptr;