Apollo  6.0
Open source self driving car software
localization_integ.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 
24 #include "localization_msf/gnss_struct.h"
25 #include "localization_msf/sins_struct.h"
27 #include "modules/drivers/gnss/proto/gnss_best_pose.pb.h"
28 #include "modules/drivers/gnss/proto/gnss_raw_observation.pb.h"
29 #include "modules/drivers/gnss/proto/heading.pb.h"
30 #include "modules/drivers/gnss/proto/imu.pb.h"
31 #include "modules/drivers/proto/pointcloud.pb.h"
34 #include "modules/localization/proto/localization.pb.h"
35 
40 namespace apollo {
41 namespace localization {
42 namespace msf {
43 
44 class LocalizationIntegImpl;
45 
53  public:
56  // Initialization.
58 
59  // Lidar pcd process.
60  void PcdProcess(const drivers::PointCloud &message);
61  // Raw Imu process.
62  // void CorrectedImuProcess(const Imu& imu_msg);
63  void RawImuProcessFlu(const drivers::gnss::Imu &imu_msg);
64  void RawImuProcessRfu(const drivers::gnss::Imu &imu_msg);
65  // Gnss Info process.
67  const drivers::gnss::EpochObservation &raw_obs_msg);
68  void RawEphemerisProcess(const drivers::gnss::GnssEphemeris &gnss_orbit_msg);
69  // gnss best pose process
70  void GnssBestPoseProcess(const drivers::gnss::GnssBestPose &bestgnsspos_msg);
71  // gnss heading process
72  void GnssHeadingProcess(const drivers::gnss::Heading &gnss_heading_msg);
73 
77 
78  protected:
79  void TransferImuFlu(const drivers::gnss::Imu &imu_msg, ImuData *imu_data);
80 
81  void TransferImuRfu(const drivers::gnss::Imu &imu_msg, ImuData *imu_rfu);
82 
83  private:
84  LocalizationIntegImpl *localization_integ_impl_;
85 };
86 
87 } // namespace msf
88 } // namespace localization
89 } // namespace apollo
void TransferImuFlu(const drivers::gnss::Imu &imu_msg, ImuData *imu_data)
interface of msf localization
Definition: localization_integ_impl.h:51
void GnssBestPoseProcess(const drivers::gnss::GnssBestPose &bestgnsspos_msg)
void TransferImuRfu(const drivers::gnss::Imu &imu_msg, ImuData *imu_rfu)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
common::Status Init(const LocalizationIntegParam &params)
pcl::PointCloud< Point > PointCloud
Definition: types.h:64
interface of msf localization
Definition: localization_integ.h:52
void GnssHeadingProcess(const drivers::gnss::Heading &gnss_heading_msg)
void RawObservationProcess(const drivers::gnss::EpochObservation &raw_obs_msg)
Definition: localization_params.h:131
const LocalizationResult & GetLastestGnssLocalization() const
The class of LocalizationIntegParam.
const LocalizationResult & GetLastestLidarLocalization() const
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 & GetLastestIntegLocalization() const
void RawImuProcessRfu(const drivers::gnss::Imu &imu_msg)
void RawEphemerisProcess(const drivers::gnss::GnssEphemeris &gnss_orbit_msg)
void PcdProcess(const drivers::PointCloud &message)
void RawImuProcessFlu(const drivers::gnss::Imu &imu_msg)