Apollo  6.0
Open source self driving car software
localization_integ_impl.h
Go to the documentation of this file.
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 
31 
36 namespace apollo {
37 namespace localization {
38 namespace msf {
39 
40 class MeasureRepublishProcess;
41 class LocalizationIntegProcess;
42 class LocalizationGnssProcess;
43 class LocalizationLidarProcess;
44 
52  public:
55  // Initialization.
57 
58  // Lidar pcd process.
59  void PcdProcess(const LidarFrame& lidar_frame);
60  // Imu process.
61  void RawImuProcessRfu(const ImuData& imu_data);
62 
63  // Gnss Info process.
65  const drivers::gnss::EpochObservation& raw_obs_msg);
66  void RawEphemerisProcess(const drivers::gnss::GnssEphemeris& gnss_orbit_msg);
67 
68  // gnss best pose process
69  void GnssBestPoseProcess(const drivers::gnss::GnssBestPose& bestgnsspos_msg);
70 
71  // gnss heading process
72  void GnssHeadingProcess(const drivers::gnss::Heading& gnssheading_msg);
73 
75 
77 
79 
80  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
81 
82  protected:
83  void PcdProcessImpl(const LidarFrame& pcd_data);
84 
85  void ImuProcessImpl(const ImuData& imu_data);
86 
88  const drivers::gnss::EpochObservation& raw_obs_msg);
90  const drivers::gnss::GnssEphemeris& gnss_orbit_msg);
92  const drivers::gnss::GnssBestPose& bestgnsspos_msg);
93 
94  void GnssHeadingProcessImpl(const drivers::gnss::Heading& gnssheading_msg);
95 
96  void TransferGnssMeasureToLocalization(const MeasureData& measure,
97  LocalizationEstimate* localization);
98 
99  private:
100  MeasureRepublishProcess* republish_process_;
101  LocalizationIntegProcess* integ_process_;
102  LocalizationGnssProcess* gnss_process_;
103  LocalizationLidarProcess* lidar_process_;
104 
105  LocalizationResult lastest_lidar_localization_;
106  LocalizationResult lastest_integ_localization_;
107  LocalizationResult lastest_gnss_localization_;
108 
109  bool is_use_gnss_bestpose_ = true;
110 
111  double imu_altitude_from_lidar_localization_ = 0.0;
112  bool imu_altitude_from_lidar_localization_available_ = false;
113 
114  bool enable_lidar_localization_ = true;
115  Eigen::Affine3d gnss_antenna_extrinsic_;
116  OnlineLocalizationExpert expert_;
117 };
118 
119 } // namespace msf
120 } // namespace localization
121 } // namespace apollo
interface of msf localization
Definition: localization_integ_impl.h:51
void RawEphemerisProcess(const drivers::gnss::GnssEphemeris &gnss_orbit_msg)
void RawImuProcessRfu(const ImuData &imu_data)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void GnssHeadingProcess(const drivers::gnss::Heading &gnssheading_msg)
process lidar msg for localization
Definition: measure_republish_process.h:62
void RawObservationProcessImpl(const drivers::gnss::EpochObservation &raw_obs_msg)
void GnssBestPoseProcess(const drivers::gnss::GnssBestPose &bestgnsspos_msg)
process Imu msg for localization
Definition: localization_integ_process.h:47
void GnssBestPoseProcessImpl(const drivers::gnss::GnssBestPose &bestgnsspos_msg)
const LocalizationResult & GetLastestLidarLocalization() const
void PcdProcess(const LidarFrame &lidar_frame)
The class of LocalizationLidarProcess.
void GnssHeadingProcessImpl(const drivers::gnss::Heading &gnssheading_msg)
The class of MeasureRepublishProcess.
process lidar msg for localization
Definition: localization_lidar_process.h:70
Definition: localization_params.h:131
The class of LocalizationInteg.
Definition: online_localization_expert.h:33
void TransferGnssMeasureToLocalization(const MeasureData &measure, LocalizationEstimate *localization)
void ImuProcessImpl(const ImuData &imu_data)
void RawEphemerisProcessImpl(const drivers::gnss::GnssEphemeris &gnss_orbit_msg)
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
const LocalizationResult & GetLastestGnssLocalization() const
Definition: localization_gnss_process.h:101
The class of LocalizationGnssProcess.
void RawObservationProcess(const drivers::gnss::EpochObservation &raw_obs_msg)
const LocalizationResult & GetLastestIntegLocalization() const
common::Status Init(const LocalizationIntegParam &params)
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Definition: localization_lidar.h:36
void PcdProcessImpl(const LidarFrame &pcd_data)