Apollo 10.0
自动驾驶开放平台
measure_republish_process.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 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 <list>
25#include <mutex>
26#include <string>
27
28#include "Eigen/Core"
29#include "Eigen/Geometry"
30#include "localization_msf/sins_struct.h"
32#include "modules/common_msgs/sensor_msgs/gnss_best_pose.pb.h"
33#include "modules/common_msgs/sensor_msgs/heading.pb.h"
36#include "modules/common_msgs/localization_msgs/localization.pb.h"
37
42namespace apollo {
43namespace localization {
44namespace msf {
45
46enum class GnssMode { NOVATEL = 0, SELF };
47
50 TransformD transform_1;
51 TransformD transform_2;
52
53 public:
54 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55};
56
63 public:
65
68 // Initialization.
70
71 // GNSS message process
72 bool NovatelBestgnssposProcess(const GnssBestPose& bestgnsspos_msg,
73 MeasureData* measure);
74 void GnssLocalProcess(const MeasureData& gnss_local_msg,
75 MeasureData* measure);
76
77 // integrated message process
78 void IntegPvaProcess(const InsPva& inspva_msg);
79
80 // lidar message process
81 bool LidarLocalProcess(const LocalizationEstimate& lidar_local_msg,
82 MeasureData* measure);
83
84 bool GnssHeadingProcess(const drivers::gnss::Heading& heading_msg,
85 MeasureData* measure, int* status);
86
87 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88
89 protected:
90 bool IsSinsAlign();
91 bool CheckBestgnssposeStatus(const GnssBestPose& bestgnsspos_msg);
92 bool CheckBestgnssPoseXYStd(const GnssBestPose& bestgnsspos_msg);
93 void TransferXYZFromBestgnsspose(const GnssBestPose& bestgnsspos_msg,
94 MeasureData* measure);
95 void TransferFirstMeasureFromBestgnsspose(const GnssBestPose& bestgnsspos_msg,
96 MeasureData* measure);
97 bool CalculateVelFromBestgnsspose(const GnssBestPose& bestgnsspos_msg,
98 MeasureData* measure);
99
100 bool LoadImuGnssAntennaExtrinsic(std::string file_path,
101 VehicleGnssAntExtrinsic* extrinsic) const;
102
103 private:
104 MeasureData pre_bestgnsspose_;
105 bool pre_bestgnsspose_valid_;
106 bool send_init_bestgnsspose_;
107
108 std::list<InsPva> integ_pva_list_;
109 size_t pva_buffer_size_;
110 std::mutex integ_pva_mutex_;
111
112 int local_utm_zone_id_;
113 bool is_trans_gpstime_to_utctime_;
114
115 double map_height_time_;
116 std::mutex height_mutex_;
117
118 bool is_using_novatel_heading_;
119 double novatel_heading_time_;
120 std::mutex novatel_heading_mutex_;
121
122 GnssMode gnss_mode_;
123
124 static constexpr double GNSS_XY_STD_THRESHOLD = 5.0;
125 static constexpr double BESTPOSE_TIME_MAX_INTERVAL = 1.05;
126 static constexpr int BESTPOSE_GOOD_COUNT = 10;
127 VehicleGnssAntExtrinsic imu_gnssant_extrinsic_;
128};
129
130} // namespace msf
131} // namespace localization
132} // namespace apollo
A general class to denote the return status of an API call.
Definition status.h:43
bool LidarLocalProcess(const LocalizationEstimate &lidar_local_msg, MeasureData *measure)
void TransferFirstMeasureFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
bool LoadImuGnssAntennaExtrinsic(std::string file_path, VehicleGnssAntExtrinsic *extrinsic) const
bool NovatelBestgnssposProcess(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
void GnssLocalProcess(const MeasureData &gnss_local_msg, MeasureData *measure)
bool CalculateVelFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
bool GnssHeadingProcess(const drivers::gnss::Heading &heading_msg, MeasureData *measure, int *status)
common::Status Init(const LocalizationIntegParam &params)
bool CheckBestgnssposeStatus(const GnssBestPose &bestgnsspos_msg)
bool CheckBestgnssPoseXYStd(const GnssBestPose &bestgnsspos_msg)
void TransferXYZFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
The class of LocalizationIntegParam
class register implement
Definition arena_queue.h:37