Apollo 10.0
自动驾驶开放平台
io_util.cc
浏览该文件的文档.
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 *****************************************************************************/
17
18#include <boost/filesystem.hpp>
19
20#include "absl/strings/match.h"
21#include "yaml-cpp/yaml.h"
22
23#include "cyber/common/file.h"
24#include "cyber/common/log.h"
26
27namespace apollo {
28namespace perception {
29namespace algorithm {
30
32
33bool ReadPoseFile(const std::string &filename, Eigen::Affine3d *pose,
34 int *frame_id, double *time_stamp) {
35 if (pose == nullptr || frame_id == nullptr || time_stamp == nullptr) {
36 AERROR << "Nullptr error.";
37 return false;
38 }
39
40 std::ifstream fin(filename.c_str());
41 if (!fin.is_open()) {
42 AERROR << "Failed to open pose file: " << filename;
43 return false;
44 }
45
46 Eigen::Vector3d translation;
47 Eigen::Quaterniond quat;
48 fin >> *frame_id >> *time_stamp >> translation(0) >> translation(1) >>
49 translation(2) >> quat.x() >> quat.y() >> quat.z() >> quat.w();
50
51 *pose = Eigen::Affine3d::Identity();
52 pose->prerotate(quat);
53 pose->pretranslate(translation);
54
55 fin.close();
56 return true;
57}
58
59bool LoadBrownCameraIntrinsic(const std::string &yaml_file,
61 if (!PathExists(yaml_file) || model == nullptr) {
62 return false;
63 }
64
65 YAML::Node node = YAML::LoadFile(yaml_file);
66 if (node.IsNull()) {
67 AINFO << "Load " << yaml_file << " failed! please check!";
68 return false;
69 }
70
71 float camera_width = 0.0f;
72 float camera_height = 0.0f;
73 Eigen::VectorXf params(9 + 5 + 3); // add k4, k5, k6
74 try {
75 camera_width = node["width"].as<float>();
76 camera_height = node["height"].as<float>();
77 for (size_t i = 0; i < 9; ++i) {
78 params(i) = node["K"][i].as<float>();
79 }
80 for (size_t i = 0; i < 8; ++i) {
81 params(9 + i) = node["D"][i].as<float>();
82 }
83
84 model->set_params(static_cast<size_t>(camera_width),
85 static_cast<size_t>(camera_height), params);
86 } catch (YAML::Exception &e) {
87 AERROR << "load camera intrisic file " << yaml_file
88 << " with error, YAML exception: " << e.what();
89 return false;
90 }
91
92 return true;
93}
94
96 const std::string &yaml_file,
98 if (!PathExists(yaml_file) || model == nullptr) {
99 return false;
100 }
101
102 YAML::Node node = YAML::LoadFile(yaml_file);
103 if (node.IsNull()) {
104 AINFO << "Load " << yaml_file << " failed! please check!";
105 return false;
106 }
107
108 if (!node["width"].IsDefined() || !node["height"].IsDefined() ||
109 !node["center"].IsDefined() || !node["affine"].IsDefined() ||
110 !node["cam2world"].IsDefined() || !node["world2cam"].IsDefined() ||
111 !node["focallength"].IsDefined() || !node["principalpoint"].IsDefined()) {
112 AINFO << "Invalid intrinsics file for an omnidirectional camera.";
113 return false;
114 }
115
116 try {
117 int camera_width = 0;
118 int camera_height = 0;
119
120 std::vector<float> params; // center|affine|f|p|i,cam2world|j,world2cam
121
122 camera_width = node["width"].as<int>();
123 camera_height = node["height"].as<int>();
124
125 params.push_back(node["center"]["x"].as<float>());
126 params.push_back(node["center"]["y"].as<float>());
127
128 params.push_back(node["affine"]["c"].as<float>());
129 params.push_back(node["affine"]["d"].as<float>());
130 params.push_back(node["affine"]["e"].as<float>());
131
132 params.push_back(node["focallength"].as<float>());
133 params.push_back(node["principalpoint"]["x"].as<float>());
134 params.push_back(node["principalpoint"]["y"].as<float>());
135
136 params.push_back(static_cast<float>(node["cam2world"].size()));
137
138 for (size_t i = 0; i < node["cam2world"].size(); ++i) {
139 params.push_back(node["cam2world"][i].as<float>());
140 }
141
142 params.push_back(static_cast<float>(node["world2cam"].size()));
143
144 for (size_t i = 0; i < node["world2cam"].size(); ++i) {
145 params.push_back(node["world2cam"][i].as<float>());
146 }
147
148 Eigen::VectorXf eigen_params(params.size());
149 for (size_t i = 0; i < params.size(); ++i) {
150 eigen_params(i) = params[i];
151 }
152
153 model->set_params(camera_width, camera_height, eigen_params);
154 } catch (YAML::Exception &e) {
155 AERROR << "load camera intrisic file " << yaml_file
156 << " with error, YAML exception: " << e.what();
157 return false;
158 }
159
160 return true;
161}
162
163bool GetFileList(const std::string &path, const std::string &suffix,
164 std::vector<std::string> *files) {
165 if (!PathExists(path)) {
166 AINFO << path << " not exist.";
167 return false;
168 }
169
170 boost::filesystem::recursive_directory_iterator itr(path);
171 while (itr != boost::filesystem::recursive_directory_iterator()) {
172 try {
173 if (absl::EndsWith(itr->path().string(), suffix)) {
174 files->push_back(itr->path().string());
175 }
176 ++itr;
177 } catch (const std::exception &ex) {
178 AWARN << "Caught execption: " << ex.what();
179 continue;
180 }
181 }
182 return true;
183}
184
185} // namespace algorithm
186} // namespace perception
187} // namespace apollo
bool set_params(size_t width, size_t height, const Eigen::VectorXf &params) override
bool set_params(size_t width, size_t height, const Eigen::VectorXf &params) override
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
bool PathExists(const std::string &path)
Check if the path exists.
Definition file.cc:195
bool LoadOmnidirectionalCameraIntrinsics(const std::string &yaml_file, base::OmnidirectionalCameraDistortionModel *model)
Definition io_util.cc:95
bool GetFileList(const std::string &path, const std::string &suffix, std::vector< std::string > *files)
Definition io_util.cc:163
bool ReadPoseFile(const std::string &filename, Eigen::Affine3d *pose, int *frame_id, double *time_stamp)
Definition io_util.cc:33
bool LoadBrownCameraIntrinsic(const std::string &yaml_file, base::BrownCameraDistortionModel *model)
Definition io_util.cc:59
class register implement
Definition arena_queue.h:37