Apollo  6.0
Open source self driving car software
velodyne_utility.h
Go to the documentation of this file.
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 
22 #pragma once
23 
24 #include <string>
25 #include <vector>
26 
27 #include "Eigen/Geometry"
29 
30 namespace apollo {
31 namespace localization {
32 namespace msf {
33 
34 namespace velodyne {
35 
36 struct VelodyneFrame {
37  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39  unsigned int frame_index;
41  double timestamp;
45  std::vector<unsigned char> intensities;
47  std::vector<unsigned char> laser_ids;
50 };
51 
52 void LoadPcds(const std::string& file_path, const unsigned int frame_index,
53  const Eigen::Affine3d& pose, VelodyneFrame* velodyne_frame,
54  const bool is_global = false);
55 
56 void LoadPcds(const std::string& file_path, const unsigned int frame_index,
57  const Eigen::Affine3d& pose,
59  std::vector<unsigned char>* intensities, bool is_global = false);
60 
62 void LoadPcdPoses(const std::string& file_path,
64  std::vector<double>* timestamps);
65 
67 void LoadPcdPoses(const std::string& file_path,
69  std::vector<double>* timestamps,
70  std::vector<unsigned int>* pcd_indices);
71 
73 void LoadPosesAndStds(const std::string& file_path,
76  std::vector<double>* timestamps);
77 
78 // /**@brief Save the PCD poses with their timestamps. */
79 // void save_pcd_poses(std::string file_path,
80 // const ::apollo::common::EigenAffine3dVec& poses,
81 // const std::vector<double>& timestamps);
82 
84 bool LoadExtrinsic(const std::string& file_path, Eigen::Affine3d* extrinsic);
85 
86 } // namespace velodyne
87 } // namespace msf
88 } // namespace localization
89 } // namespace apollo
EigenVector< Eigen::Affine3d > EigenAffine3dVec
Definition: eigen_defs.h:39
void LoadPosesAndStds(const std::string &file_path, ::apollo::common::EigenAffine3dVec *poses, ::apollo::common::EigenVector3dVec *stds, std::vector< double > *timestamps)
Load poses and stds their timestamps.
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
EIGEN_MAKE_ALIGNED_OPERATOR_NEW unsigned int frame_index
The frame index.
Definition: velodyne_utility.h:39
double timestamp
The time stamp.
Definition: velodyne_utility.h:41
std::vector< unsigned char > laser_ids
The laser IDs.
Definition: velodyne_utility.h:47
bool LoadExtrinsic(const std::string &file_path, Eigen::Affine3d *extrinsic)
Save the PCD poses with their timestamps.
void LoadPcdPoses(const std::string &file_path, ::apollo::common::EigenAffine3dVec *poses, std::vector< double > *timestamps)
Load the PCD poses with their timestamps.
::apollo::common::EigenVector3dVec pt3ds
The 3D point cloud in this frame.
Definition: velodyne_utility.h:43
EigenVector< Eigen::Vector3d > EigenVector3dVec
Definition: eigen_defs.h:38
void LoadPcds(const std::string &file_path, const unsigned int frame_index, const Eigen::Affine3d &pose, VelodyneFrame *velodyne_frame, const bool is_global=false)
Eigen::Affine3d pose
The pose of the frame.
Definition: velodyne_utility.h:49
std::vector< unsigned char > intensities
The laser reflection values in this frames.
Definition: velodyne_utility.h:45
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34