28 #include "gtest/gtest_prod.h" 31 #include "Eigen/Geometry" 33 #include "modules/drivers/gnss/proto/gnss_best_pose.pb.h" 34 #include "modules/drivers/gnss/proto/gnss_raw_observation.pb.h" 35 #include "modules/drivers/gnss/proto/imu.pb.h" 36 #include "modules/drivers/proto/pointcloud.pb.h" 37 #include "modules/localization/proto/localization.pb.h" 49 namespace localization {
51 class LocalizationMsgPublisher;
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,
90 bool LoadZoneIdFromFolder(
const std::string &folder_path,
int *zone_id);
91 void CompensateImuVehicleExtrinsic(LocalizationEstimate *local_result);
98 uint64_t pcd_msg_index_;
103 Eigen::Quaternion<double> imu_vehicle_quat_;
105 std::shared_ptr<LocalizationMsgPublisher> publisher_;
106 std::shared_ptr<drivers::gnss::Imu> raw_imu_msg_;
107 std::mutex mutex_imu_msg_;
108 std::unique_ptr<cyber::Timer> localization_timer_ =
nullptr;
void SetPublisher(const std::shared_ptr< LocalizationMsgPublisher > &publisher)
void OnGnssRtkObs(const std::shared_ptr< drivers::gnss::EpochObservation > &raw_obs_msg)
void OnPointCloud(const std::shared_ptr< drivers::PointCloud > &message)
void OnGnssRtkEph(const std::shared_ptr< drivers::gnss::GnssEphemeris > &gnss_orbit_msg)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void OnGnssBestPose(const std::shared_ptr< drivers::gnss::GnssBestPose > &bestgnsspos_msg)
void OnRawImuCache(const std::shared_ptr< drivers::gnss::Imu > &imu_msg)
interface of msf localization
Definition: localization_integ.h:52
LocalizationMeasureState
Definition: localization_params.h:129
The class of LocalizationInteg.
void OnGnssHeading(const std::shared_ptr< drivers::gnss::Heading > &gnss_heading_msg)
generate localization info based on MSF
Definition: msf_localization.h:58
void OnRawImu(const std::shared_ptr< drivers::gnss::Imu > &imu_msg)
The class of MonitorLogBuffer.
Definition: localization_params.h:60
A general class to denote the return status of an API call. It can either be an OK status for success...
Definition: status.h:43
This class help collect MonitorMessage pb to monitor topic. The messages can be published automatical...
Definition: monitor_log_buffer.h:60
void OnLocalizationTimer()
apollo::common::Status Init()