Apollo  6.0
Open source self driving car software
io_util.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 #pragma once
17 
18 #include <string>
19 #include <vector>
20 
21 #include "Eigen/Dense"
22 #include "google/protobuf/message.h"
23 
26 
27 namespace apollo {
28 namespace perception {
29 namespace common {
30 
31 bool ReadPoseFile(const std::string &filename, Eigen::Affine3d *pose,
32  int *frame_id, double *time_stamp);
33 
34 bool LoadBrownCameraIntrinsic(const std::string &yaml_file,
35  base::BrownCameraDistortionModel *model);
36 
37 // @brief: load ocam parameters
38 // https://sites.google.com/site/scarabotix/ocamcalib-toolbox
40  const std::string &yaml_file,
41  base::OmnidirectionalCameraDistortionModel *model);
42 
43 bool GetFileList(const std::string &path, const std::string &suffix,
44  std::vector<std::string> *files);
45 
46 } // namespace common
47 } // namespace perception
48 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool LoadOmnidirectionalCameraIntrinsics(const std::string &yaml_file, base::OmnidirectionalCameraDistortionModel *model)
bool GetFileList(const std::string &path, const std::string &suffix, std::vector< std::string > *files)
bool LoadBrownCameraIntrinsic(const std::string &yaml_file, base::BrownCameraDistortionModel *model)
bool ReadPoseFile(const std::string &filename, Eigen::Affine3d *pose, int *frame_id, double *time_stamp)
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34