Apollo  6.0
Open source self driving car software
localization_pose_buffer.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 
17 #pragma once
18 #include <vector>
19 
20 #include "Eigen/Core"
21 #include "Eigen/Geometry"
22 #include "Eigen/StdVector"
23 
24 namespace apollo {
25 namespace localization {
26 namespace ndt {
27 
29  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
30  double timestamp;
33 };
34 
36  public:
37  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39  ~LocalizationPoseBuffer();
43  void UpdateLidarPose(double timestamp, const Eigen::Affine3d& locator_pose,
48  Eigen::Affine3d UpdateOdometryPose(double timestamp,
49  const Eigen::Affine3d& novatel_pose);
51  unsigned int GetUsedBufferSize() { return used_buffer_size_; }
53  unsigned int GetHeadIndex() { return head_index_; }
54 
55  private:
56  static const unsigned int s_buffer_size_;
57 
58  private:
59  std::vector<LocalizationStampedPosePair,
60  Eigen::aligned_allocator<LocalizationStampedPosePair>>
61  lidar_poses_;
62  unsigned int used_buffer_size_;
63  unsigned int head_index_;
64  bool has_initialized_;
65 };
66 
67 } // namespace ndt
68 } // namespace localization
69 } // namespace apollo
unsigned int GetHeadIndex()
Get the current head of the buffer.
Definition: localization_pose_buffer.h:53
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Eigen::Affine3d novatel_pose
Definition: localization_pose_buffer.h:31
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double timestamp
Definition: localization_pose_buffer.h:30
Definition: localization_pose_buffer.h:35
Eigen::Affine3d locator_pose
Definition: localization_pose_buffer.h:32
unsigned int GetUsedBufferSize()
Get the used size of buffer.
Definition: localization_pose_buffer.h:51
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
Definition: localization_pose_buffer.h:28