Skip to content

Commit

Permalink
fix bug: cv::imread rotates images (#37)
Browse files Browse the repository at this point in the history
  • Loading branch information
oneLOH committed Mar 13, 2024
1 parent 5cd8a17 commit 3439677
Show file tree
Hide file tree
Showing 19 changed files with 106 additions and 105 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ If you use the covisibility-based matching method for your research, please cite

3.Run the following script to automatically reconstruction:
```
python3 ./scripts/auto_reconstruction.py --workspace_path ${workspace_path}$
python3 ./scripts/run_test_data.py --workspace_path ${workspace_path}$
```
Refer to [tutorial.md](docs/en/tutorial.md) for more details.

Expand Down
2 changes: 1 addition & 1 deletion README_CN.md
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ XRSfM 是一个开源的运动恢复结构代码仓库,它是[OpenXRLab](https

3.运行以下脚本进行重建:
```
python3 ./scripts/auto_reconstruction.py --workspace_path ${workspace_path}$
python3 ./scripts/run_test_data.py --workspace_path ${workspace_path}$
```
更多细节请查看[tutorial.md](docs/zh/tutorial.md)

Expand Down
2 changes: 1 addition & 1 deletion docs/en/tutorial.md
Original file line number Diff line number Diff line change
Expand Up @@ -126,5 +126,5 @@ workspace
```
Then run the following command line to reconstruct
```
python3 ./scripts/auto_reconstruction.py --workspace_path ${workspace_path}$ --estimate_scale
python3 ./scripts/run_test_data.py --workspace_path ${workspace_path}$ --estimate_scale
```
2 changes: 1 addition & 1 deletion docs/zh/tutorial.md
Original file line number Diff line number Diff line change
Expand Up @@ -130,5 +130,5 @@ workspace
```
然后通过以下脚本达到相同的效果。
```
python3 ./scripts/auto_reconstruction.py --workspace_path ${workspace_path}$ --estimate_scale
python3 ./scripts/run_test_data.py --workspace_path ${workspace_path}$ --estimate_scale
```
20 changes: 17 additions & 3 deletions scripts/auto_reconstruction.py → scripts/run_test_data.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,24 @@ def get_opts():
parser = ArgumentParser()
parser.add_argument('--workspace_path', type=str, required=True,
help='workspace_path')
# parser.add_argument('--start_from_ios_binary',action='store_true',
# help='estimate_scale')
parser.add_argument('--estimate_scale', action='store_true',
help='estimate_scale')
# parser.add_argument('--start_from_ios_binary',action='store_true',
# help='estimate_scale')
return parser.parse_args()


def change_camera_txt_format(data_path):
with open(data_path+'/camera.txt', 'r') as file:
line = file.readline()

space_index1 = line.find(' ')
space_index2 = line.find(' ', space_index1 + 1)

with open(data_path+'/camera_colmap.txt', 'w') as file:
file.write(f'0 RADIAL 1440 1920 {line[space_index2+1:]}')


if __name__ == '__main__':
args = get_opts()

Expand All @@ -22,18 +33,21 @@ def get_opts():
data_path = data_path+'/'

images_path = data_path+'images/'
camera_path = data_path+'camera.txt'
camera_path = data_path+'camera_colmap.txt'
retrieval_path = data_path+'retrieval.txt'

output_path = data_path

# if(args.start_from_ios_binary):
# ios_file = data_path+'Data.txt'
# os.system('./bin/unpack_collect_data '+ios_file+' '+data_path)
change_camera_txt_format(data_path)

os.system('./bin/run_matching ' + images_path + ' ' + retrieval_path
+ ' sequential ' + output_path)
os.system('./bin/run_reconstruction ' + output_path + ' '
+ camera_path + ' ' + output_path)

if (args.estimate_scale):
output_refined_path = data_path+'refined/'
if not os.path.exists(output_refined_path):
Expand Down
19 changes: 19 additions & 0 deletions src/base/camera.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,24 @@ namespace xrsfm {
class Camera {
public:
Camera() {}
Camera(int _id, std::string mode_name, int w, int h) {
id_ = _id;
width_ = w;
height_ = h;
if (mode_name == "SIMPLE_PINHOLE") {
model_id_ = 0;
} else if (mode_name == "PINHOLE") {
model_id_ = 1;
} else if (mode_name == "SIMPLE_RADIAL") {
model_id_ = 2;
} else if (mode_name == "RADIAL") {
model_id_ = 3;
} else if (mode_name == "OPENCV") {
model_id_ = 4;
}
params_.resize(camera_model_param_size(model_id_));
is_valid = true;
}
Camera(int _id, int _model_id) {
id_ = _id;
model_id_ = _model_id;
Expand All @@ -26,6 +44,7 @@ class Camera {

uint32_t id_ = -1;
uint32_t model_id_ = -1;
int width_, height_;
std::vector<double> params_;
bool is_valid;

Expand Down
22 changes: 11 additions & 11 deletions src/base/camera_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,17 +219,6 @@ struct OpenCVCameraModel {

#endif

inline int camera_model_param_size(int model_id) {
#define CAMERA_MODEL_CASE(CameraModel) \
if (model_id == CameraModel::kModelId) \
return CameraModel::kNumParams;

CAMERA_MODEL_CASES
#undef CAMERA_MODEL_CASE
assert(false);
return -1;
}

inline int index_fx(int model_id) {
#define CAMERA_MODEL_CASE(CameraModel) \
if (model_id == CameraModel::kModelId) \
Expand Down Expand Up @@ -285,5 +274,16 @@ inline int index_distort(int model_id) {
return -1;
};

inline int camera_model_param_size(int model_id) {
#define CAMERA_MODEL_CASE(CameraModel) \
if (model_id == CameraModel::kModelId) \
return CameraModel::kNumParams;

CAMERA_MODEL_CASES
#undef CAMERA_MODEL_CASE
assert(false);
return -1;
}

} // namespace xrsfm
#endif
3 changes: 0 additions & 3 deletions src/base/map.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,9 +115,6 @@ class CorrespondenceGraph {

class Map {
public:
std::vector<cv::Mat> images_; // for debug

// std::vector<Camera> cameras_;
std::vector<Track> tracks_;
std::vector<Frame> frames_;
std::vector<FramePair> frame_pairs_;
Expand Down
4 changes: 2 additions & 2 deletions src/feature/feature_extraction.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
#include "optim/loransac.h"
#include "optim/ransac.h"
#include "sift_extractor.h"
#include "utility/io_ecim.hpp"
#include "utility/timer.h"

namespace xrsfm {
Expand All @@ -38,7 +37,8 @@ void FeatureExtract(const std::string &image_dir_path,
for (int i = 0; i < frames.size(); i++) {
Frame &frame = frames[i];
frame.keypoints_.clear();
const cv::Mat image = cv::imread(image_dir_path + frame.name);
const cv::Mat image = cv::imread(image_dir_path + frame.name,
cv::IMREAD_IGNORE_ORIENTATION);
if (image.rows == 0) {
std::cout << "Can't read " << image_dir_path + frame.name
<< std::endl;
Expand Down
1 change: 0 additions & 1 deletion src/feature/feature_processing.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#include "optim/loransac.h"
#include "optim/ransac.h"
#include "sift_extractor.h"
#include "utility/io_ecim.hpp"
#include "utility/timer.h"
#include "match_expansion.h"

Expand Down
10 changes: 0 additions & 10 deletions src/geometry/error_corrector.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,11 @@ inline double ToDeg(double theta) { return theta * 180 / M_PI; }

class ErrorDetector {
public:
Init(std::string image_dir, bool debug) {
debug_ = debug;
image_dir_ = image_dir;
};

bool CheckAllRelativePose(Map &map, int frame_id,
std::set<int> &bad_matched_frame_ids);
bool IsGoodRelativePose(const Map &map, const FramePair &fp,
std::vector<char> &inlier_mask);
void IsGoodRelativePose_Debug(Map &map, FramePair &fp,
const std::vector<char> &inlier_mask);
// void StoreRelativePose(Map &map, int frame_id, std::ofstream &file);

bool debug_;
// ViewerThread *viewerTh_;
std::string image_dir_;
};

Expand Down
41 changes: 0 additions & 41 deletions src/geometry/error_detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,29 +100,6 @@ bool ErrorDetector::IsGoodRelativePose(const Map &map, const FramePair &fp,
return true;
}

void ErrorDetector::IsGoodRelativePose_Debug(
Map &map, FramePair &fp, const std::vector<char> &inlier_mask) {
auto &frame1 = map.frames_[fp.id1];
auto &frame2 = map.frames_[fp.id2];
cv::Mat image1 = cv::imread(image_dir_ + frame1.name);
cv::Mat image2 = cv::imread(image_dir_ + frame2.name);
if (image1.empty() || image2.empty()) {
printf("%s\n", (image_dir_ + frame1.name).c_str());
} else {
// DrawFeatureMatches(image1, image2, frame1.points, frame2.points,
// fp.matches, inlier_mask);
// DrawFeatureMatches1(image1, frame1.points, frame2.points, fp.matches,
// inlier_mask);
}
// frame1.flag_for_view = frame2.flag_for_view = true;
// viewer_->Draw(map, true);
// frame1.flag_for_view = frame2.flag_for_view = false;
frame1.flag_for_view = frame2.flag_for_view = true;
// viewerTh_->update_map(map);
frame1.flag_for_view = frame2.flag_for_view = false;
cv::waitKey();
}

bool ErrorDetector::CheckAllRelativePose(Map &map, int frame_id,
std::set<int> &bad_matched_frame_ids) {
bad_matched_frame_ids.clear();
Expand Down Expand Up @@ -170,7 +147,6 @@ bool ErrorDetector::CheckAllRelativePose(Map &map, int frame_id,
} else {
int bad_neighbor_id = fp.id1 == frame_id ? fp.id2 : fp.id1;
bad_matched_frame_ids.insert(bad_neighbor_id);
// if (debug_) IsGoodRelativePose_Debug(map, fp, inlier_mask);
}
}
}
Expand All @@ -182,21 +158,4 @@ bool ErrorDetector::CheckAllRelativePose(Map &map, int frame_id,
return true;
}

// void ErrorDetector::StoreRelativePose(Map &map, int frame_id,
// std::ofstream &file) {
// for (const auto id : map.frameid2framepairids_[frame_id]) {
// auto &fp = map.frame_pairs_[id];
// const auto &frame1 = map.frames_[fp.id1];
// const auto &frame2 = map.frames_[fp.id2];
// if (frame1.registered && frame2.registered && frame1.is_keyframe &&
// frame2.is_keyframe) {
// file << id << std::endl;
// file << frame1.Tcw.q.coeffs().transpose() << " "
// << frame1.Tcw.t.transpose() << std::endl;
// file << frame2.Tcw.q.coeffs().transpose() << " "
// << frame2.Tcw.t.transpose() << std::endl;
// }
// }
// file << "-1" << std::endl;
// }
} // namespace xrsfm
1 change: 0 additions & 1 deletion src/optimization/ba_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -672,7 +672,6 @@ void BASolver::KGBA(Map &map, const std::vector<int> fix_key_frame_ids,
ceres::Solve(solver_options, &problem, &summary);
// std::cout << summary.BriefReport() << "\n";
PrintSolverSummary(summary);
map.Camera(0).log();

printf("kf: %d/%d\n", num_kf, num_rf);
UpdateByRefFrame(map);
Expand Down
27 changes: 17 additions & 10 deletions src/run_matching.cc
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,16 @@

using namespace xrsfm;

void GetFeatures(const std::string &images_path, const std::string &ftr_path,
std::vector<Frame> &frames) {
void GetFeatures(const std::string &images_path,
const std::vector<std::string> &image_names,
const std::string &ftr_path, std::vector<Frame> &frames) {
const int num_image = image_names.size();
frames.resize(num_image);
for (int i = 0; i < num_image; ++i) {
frames[i].id = i;
frames[i].name = image_names[i];
}

std::ifstream ftr_bin(ftr_path);
if (ftr_bin.good()) {
ReadFeatures(ftr_path, frames);
Expand All @@ -33,7 +41,8 @@ void GetImageSizeVec(const std::string &images_path,
LoadImageSize(path, image_size);
} else {
for (const auto &image_name : image_names) {
const cv::Mat image = cv::imread(images_path + image_name);
const cv::Mat image = cv::imread(images_path + image_name,
cv::IMREAD_IGNORE_ORIENTATION);
image_size.push_back(ImageSize(image.cols, image.rows));
}
SaveImageSize(path, image_size);
Expand Down Expand Up @@ -173,27 +182,25 @@ int main(int argc, const char *argv[]) {
const std::string fp_init_path = output_path + "fp_init.bin";
const std::string fp_path = output_path + "fp.bin";

// 1.read imagesstd::filesystem
// 1.read images
if (!std::experimental::filesystem::exists(images_path)) {
std::cout << "image path not exists :" << images_path << "\n";
exit(-1);
}
std::vector<std::string> image_names;
LoadImageNames(images_path, image_names);
std::vector<ImageSize> image_size_vec;
GetImageSizeVec(images_path, image_names, size_path, image_size_vec);
std::map<std::string, int> name2id;
const int num_image = image_names.size();
std::vector<Frame> frames(num_image);
for (int i = 0; i < num_image; ++i) {
frames[i].id = i;
frames[i].name = image_names[i];
name2id[image_names[i]] = i;
}
std::cout << "Load Image Info Done.\n";

// 2.feature extraction
GetFeatures(images_path, ftr_path, frames);
std::vector<Frame> frames;
std::vector<ImageSize> image_size_vec;
GetFeatures(images_path, image_names, ftr_path, frames);
GetImageSizeVec(images_path, image_names, size_path, image_size_vec);
std::cout << "Extract Features Done.\n";

// 5.image matching
Expand Down
8 changes: 5 additions & 3 deletions src/run_reconstruction.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,12 @@ void PreProcess(const std::string dir_path, const std::string camera_path,
std::cout << "ReadFramePairs\n";

// set cameras & image name
Camera seq = ReadCameraIOSRecord(camera_path);
std::map<int, Camera> cameras = ReadCamerasText(camera_path);
CHECK_EQ(cameras.size(), 1);
const int camera_id = cameras.begin()->first;

for (auto &frame : frames) {
frame.camera_id = seq.id_;
frame.camera_id = camera_id;
}

// convert keypoint to points(for reconstruction)
Expand All @@ -36,7 +38,7 @@ void PreProcess(const std::string dir_path, const std::string camera_path,
}
}

map.camera_map_[seq.id_] = seq;
map.camera_map_ = cameras;
map.frames_ = frames;
map.frame_pairs_ = frame_pairs;

Expand Down
5 changes: 2 additions & 3 deletions src/tag/tag_extract.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ extern "C" {
#include "optimization/cost_factor_ceres.h"
#include "utility/io_ecim.hpp"
#include "utility/timer.h"
// #include "utility/viewer.h"

namespace xrsfm {

Expand All @@ -48,7 +47,7 @@ tag_extract(std::string image_dir) {
for (auto &image_name : image_vec) {
std::string img_path = image_dir + image_name;
cv::Mat frame, gray;
frame = cv::imread(img_path.c_str());
frame = cv::imread(img_path.c_str(), cv::IMREAD_IGNORE_ORIENTATION);
cv::cvtColor(frame, gray, cv::COLOR_BGR2GRAY);
image_u8_t im = {.width = gray.cols,
.height = gray.rows,
Expand Down Expand Up @@ -90,7 +89,7 @@ tag_extract(const std::string &image_dir,
for (auto &image_name : image_vec) {
std::string img_path = image_dir + image_name;
cv::Mat frame, gray;
frame = cv::imread(img_path.c_str());
frame = cv::imread(img_path.c_str(), cv::IMREAD_IGNORE_ORIENTATION);
cv::cvtColor(frame, gray, cv::COLOR_BGR2GRAY);
image_u8_t im = {.width = gray.cols,
.height = gray.rows,
Expand Down
4 changes: 4 additions & 0 deletions src/utility/io_ecim.cc
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,10 @@ void WritePoints3DBinary(const std::string &path,
}

void WriteColMapDataBinary(const std::string &output_path, const Map &map) {
namespace fs = std::experimental::filesystem;
if (!fs::is_directory(output_path)) {
fs::create_directories(output_path);
}
WriteCamerasBinary(output_path + "cameras.bin", map.camera_map_);
WriteImagesBinary(output_path + "images.bin", map.frames_);
WritePoints3DBinary(output_path + "points3D.bin", map.tracks_);
Expand Down
Loading

0 comments on commit 3439677

Please sign in to comment.