Apollo 10.0
自动驾驶开放平台
msf_localization.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
22#pragma once
23
24#include <memory>
25#include <mutex>
26#include <string>
27
28#include "gtest/gtest_prod.h"
29
30#include "Eigen/Core"
31#include "Eigen/Geometry"
32
33#include "modules/common_msgs/sensor_msgs/gnss_best_pose.pb.h"
34#include "modules/common_msgs/sensor_msgs/gnss_raw_observation.pb.h"
35#include "modules/common_msgs/sensor_msgs/imu.pb.h"
36#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
37#include "modules/common_msgs/localization_msgs/localization.pb.h"
38
39#include "cyber/common/log.h"
43
48namespace apollo {
49namespace localization {
50
51class LocalizationMsgPublisher;
52
59 public:
60 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61
62 public:
64
66 void InitParams();
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);
70 void OnGnssRtkObs(
71 const std::shared_ptr<drivers::gnss::EpochObservation> &raw_obs_msg);
72 void OnGnssRtkEph(
73 const std::shared_ptr<drivers::gnss::GnssEphemeris> &gnss_orbit_msg);
74 void OnGnssBestPose(
75 const std::shared_ptr<drivers::gnss::GnssBestPose> &bestgnsspos_msg);
76 void OnGnssHeading(
77 const std::shared_ptr<drivers::gnss::Heading> &gnss_heading_msg);
78
79 void SetPublisher(const std::shared_ptr<LocalizationMsgPublisher> &publisher);
81
82 private:
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);
91 void CompensateImuVehicleExtrinsic(LocalizationEstimate *local_result);
92
93 private:
95 msf::LocalizationInteg localization_integ_;
96 msf::LocalizationIntegParam localization_param_;
97 msf::LocalizationMeasureState localization_state_;
98 uint64_t pcd_msg_index_;
99
100 // FRIEND_TEST(MSFLocalizationTest, InitParams);
101
102 // rotation from the vehicle coord to imu coord
103 Eigen::Quaternion<double> imu_vehicle_quat_;
104 Eigen::Vector3d imu_vehicle_translation_;
105
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;
110};
111
112} // namespace localization
113} // namespace apollo
A general class to denote the return status of an API call.
Definition status.h:43
generate localization info based on MSF
void SetPublisher(const std::shared_ptr< LocalizationMsgPublisher > &publisher)
void OnRawImu(const std::shared_ptr< drivers::gnss::Imu > &imu_msg)
void OnPointCloud(const std::shared_ptr< drivers::PointCloud > &message)
void OnGnssBestPose(const std::shared_ptr< drivers::gnss::GnssBestPose > &bestgnsspos_msg)
void OnRawImuCache(const std::shared_ptr< drivers::gnss::Imu > &imu_msg)
void OnGnssHeading(const std::shared_ptr< drivers::gnss::Heading > &gnss_heading_msg)
void OnGnssRtkEph(const std::shared_ptr< drivers::gnss::GnssEphemeris > &gnss_orbit_msg)
void OnGnssRtkObs(const std::shared_ptr< drivers::gnss::EpochObservation > &raw_obs_msg)
The class of LocalizationInteg
The class of MonitorLogBuffer
class register implement
Definition arena_queue.h:37