Apollo 10.0
自动驾驶开放平台
rtk_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
17#pragma once
18
19#include <list>
20#include <memory>
21#include <string>
22#include <vector>
23
24#include "gtest/gtest_prod.h"
25
27#include "modules/common_msgs/sensor_msgs/ins.pb.h"
28#include "modules/common_msgs/localization_msgs/gps.pb.h"
29#include "modules/common_msgs/localization_msgs/imu.pb.h"
30#include "modules/common_msgs/localization_msgs/localization.pb.h"
31#include "modules/localization/proto/rtk_config.pb.h"
32
33namespace apollo {
34namespace localization {
35
37 public:
39 ~RTKLocalization() = default;
40
41 void InitConfig(const rtk_config::Config &config);
42
43 void GpsCallback(const std::shared_ptr<localization::Gps> &gps_msg);
45 const std::shared_ptr<drivers::gnss::InsStat> &status_msg);
46 void ImuCallback(const std::shared_ptr<localization::CorrectedImu> &imu_msg);
47
48 bool IsServiceStarted();
49 void GetLocalization(LocalizationEstimate *localization);
50 void GetLocalizationStatus(LocalizationStatus *localization_status);
51
52 private:
53 void RunWatchDog(double gps_timestamp);
54
55 void PrepareLocalizationMsg(const localization::Gps &gps_msg,
56 LocalizationEstimate *localization,
57 LocalizationStatus *localization_status);
58 void ComposeLocalizationMsg(const localization::Gps &gps,
60 LocalizationEstimate *localization);
61 void FillLocalizationMsgHeader(LocalizationEstimate *localization);
62 void FillLocalizationStatusMsg(const drivers::gnss::InsStat &status,
63 LocalizationStatus *localization_status);
64
65 bool FindMatchingIMU(const double gps_timestamp_sec, CorrectedImu *imu_msg);
66 bool InterpolateIMU(const CorrectedImu &imu1, const CorrectedImu &imu2,
67 const double timestamp_sec, CorrectedImu *imu_msg);
68 template <class T>
69 T InterpolateXYZ(const T &p1, const T &p2, const double frac1);
70
71 bool FindNearestGpsStatus(const double gps_timestamp_sec,
73
74 private:
75 std::string module_name_ = "localization";
76
77 std::list<localization::CorrectedImu> imu_list_;
78 size_t imu_list_max_size_ = 50;
79 std::mutex imu_list_mutex_;
80
81 std::list<drivers::gnss::InsStat> gps_status_list_;
82 size_t gps_status_list_max_size_ = 10;
83 std::mutex gps_status_list_mutex_;
84
85 std::vector<double> map_offset_;
86
87 double gps_time_delay_tolerance_ = 1.0;
88 double gps_imu_time_diff_threshold_ = 0.02;
89 double gps_status_time_diff_threshold_ = 1.0;
90
91 double last_received_timestamp_sec_ = 0.0;
92 double last_reported_timestamp_sec_ = 0.0;
93
94 bool enable_watch_dog_ = true;
95 bool service_started_ = false;
96 double service_started_time = 0.0;
97
98 int64_t localization_seq_num_ = 0;
99 LocalizationEstimate last_localization_result_;
100 LocalizationStatus last_localization_status_result_;
101
102 int localization_publish_freq_ = 100;
103 int report_threshold_err_num_ = 10;
104 int service_delay_threshold = 1;
106
107 FRIEND_TEST(RTKLocalizationTest, InterpolateIMU);
108 FRIEND_TEST(RTKLocalizationTest, ComposeLocalizationMsg);
109};
110
111} // namespace localization
112} // namespace apollo
void GpsStatusCallback(const std::shared_ptr< drivers::gnss::InsStat > &status_msg)
void ImuCallback(const std::shared_ptr< localization::CorrectedImu > &imu_msg)
void InitConfig(const rtk_config::Config &config)
void GetLocalization(LocalizationEstimate *localization)
void GpsCallback(const std::shared_ptr< localization::Gps > &gps_msg)
void GetLocalizationStatus(LocalizationStatus *localization_status)
The class of MonitorLogBuffer
class register implement
Definition arena_queue.h:37