18#include <boost/filesystem.hpp>
20#include "absl/strings/match.h"
21#include "yaml-cpp/yaml.h"
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.";
40 std::ifstream fin(filename.c_str());
42 AERROR <<
"Failed to open pose file: " << filename;
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();
51 *pose = Eigen::Affine3d::Identity();
52 pose->prerotate(quat);
53 pose->pretranslate(translation);
61 if (!PathExists(yaml_file) || model ==
nullptr) {
65 YAML::Node node = YAML::LoadFile(yaml_file);
67 AINFO <<
"Load " << yaml_file <<
" failed! please check!";
71 float camera_width = 0.0f;
72 float camera_height = 0.0f;
73 Eigen::VectorXf params(9 + 5 + 3);
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>();
80 for (
size_t i = 0; i < 8; ++i) {
81 params(9 + i) = node[
"D"][i].as<
float>();
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();
96 const std::string &yaml_file,
98 if (!PathExists(yaml_file) || model ==
nullptr) {
102 YAML::Node node = YAML::LoadFile(yaml_file);
104 AINFO <<
"Load " << yaml_file <<
" failed! please check!";
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.";
117 int camera_width = 0;
118 int camera_height = 0;
120 std::vector<float> params;
122 camera_width = node[
"width"].as<
int>();
123 camera_height = node[
"height"].as<
int>();
125 params.push_back(node[
"center"][
"x"].as<float>());
126 params.push_back(node[
"center"][
"y"].as<float>());
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>());
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>());
136 params.push_back(
static_cast<float>(node[
"cam2world"].size()));
138 for (
size_t i = 0; i < node[
"cam2world"].size(); ++i) {
139 params.push_back(node[
"cam2world"][i].as<float>());
142 params.push_back(
static_cast<float>(node[
"world2cam"].size()));
144 for (
size_t i = 0; i < node[
"world2cam"].size(); ++i) {
145 params.push_back(node[
"world2cam"][i].as<float>());
148 Eigen::VectorXf eigen_params(params.size());
149 for (
size_t i = 0; i < params.size(); ++i) {
150 eigen_params(i) = params[i];
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();
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.";
170 boost::filesystem::recursive_directory_iterator itr(path);
171 while (itr != boost::filesystem::recursive_directory_iterator()) {
173 if (absl::EndsWith(itr->path().string(), suffix)) {
174 files->push_back(itr->path().string());
177 }
catch (
const std::exception &ex) {
178 AWARN <<
"Caught execption: " << ex.what();
bool set_params(size_t width, size_t height, const Eigen::VectorXf ¶ms) override
bool set_params(size_t width, size_t height, const Eigen::VectorXf ¶ms) override
bool PathExists(const std::string &path)
Check if the path exists.
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 ReadPoseFile(const std::string &filename, Eigen::Affine3d *pose, int *frame_id, double *time_stamp)
bool LoadBrownCameraIntrinsic(const std::string &yaml_file, base::BrownCameraDistortionModel *model)