Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
{
"files.associations": {
"ostream": "cpp"
}
}
1 change: 1 addition & 0 deletions apps/endomapper.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ int main(int argc, char **argv) {

SLAM.TrackImage(*image);
}
SLAM.SaveTraj();

return 0;
}
1 change: 1 addition & 0 deletions apps/hamlyn.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ int main(int argc, char **argv) {

SLAM.TrackImageWithStereo(*im_left, *im_right);
}
SLAM.SaveTraj();

return 0;
}
1 change: 1 addition & 0 deletions apps/simulation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ int main(int argc, char **argv) {

SLAM.TrackImageWithDepth((*image), (*depth_image));
}
SLAM.SaveTraj();

return 0;
}
53 changes: 53 additions & 0 deletions modules/SLAM/system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,8 @@ System::System(const string settings_file_path) {
// Initialize frame evaluator.
FrameEvaluator::Options frame_evaluator_options;
frame_evaluator_options.results_file_path = settings_->GetEvaluationPath();
cout << "Evaluation path: " << settings_->GetEvaluationPath() << endl;

frame_evaluator_options.precomputed_depth_ = true;
frame_evaluator_ = make_unique<FrameEvaluator>(frame_evaluator_options, stereo_pattern_matcher_,
map_visualizer_.get());
Expand All @@ -110,6 +112,57 @@ System::~System() {
map_visualizer_thread_->join();
}

vector<Eigen::Vector3f> System::GetTraj() {
auto latest_frames = map_->GetTemporalBuffer()->GetLatestCameraPoses();

vector<Eigen::Vector3f> trajectory;
for (auto& pose : latest_frames) {
trajectory.push_back(pose.inverse().translation());
}
return trajectory;
}


void System::SaveTraj() {
// Get the latest camera poses directly (not just translation)
// auto latest_frames = map_->GetTemporalBuffer()->GetLatestCameraPoses();
auto poses = tracker_->GetCameraPoses();

// Open file for writing
std::ofstream traj_file("trajectory.tum", std::ios::out);
if (!traj_file.is_open()) {
std::cerr << "Failed to open trajectory file!" << std::endl;
return;
}

// Set precision for floating-point output
traj_file << std::fixed << std::setprecision(6);

// Iterate over poses and write in TUM format
double time_step = 0.033; // Assume 30 FPS; adjust as needed
int frame_idx = 0;
for (const auto& pose : poses) {
// Assuming pose is Sophus::SE3f or Sophus::SE3d
Eigen::Vector3f t = pose.inverse().translation(); // Translation (x, y, z)
Eigen::Quaternionf q(pose.inverse().unit_quaternion()); // Quaternion (qx, qy, qz, qw)

// Synthetic timestamp (adjust if real timestamps are available)
double timestamp = frame_idx * time_step;

// Write to file: timestamp tx ty tz qx qy qz qw
traj_file << timestamp << " "
<< t.x() << " " << t.y() << " " << t.z() << " "
<< q.x() << " " << q.y() << " " << q.z() << " " << q.w() << "\n";

frame_idx++;
}

// Close the file
traj_file.close();
std::cout << "Trajectory saved to trajectory.tum" << std::endl;
}


void System::TrackImage(const cv::Mat &im) {
// Preprocess image.
cv::Mat im_gray;
Expand Down
8 changes: 8 additions & 0 deletions modules/SLAM/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,10 @@
#include <memory>
#include <thread>

#include <fstream>
#include <iomanip>
#include <Eigen/Geometry>

#include "map/map.h"
#include "mapping/mapping.h"
#include "SLAM/settings.h"
Expand Down Expand Up @@ -53,6 +57,10 @@ class System {
// TODO: implement stereo options
void TrackImageWithStereo(const cv::Mat& im_left, const cv::Mat& im_right);

vector<Eigen::Vector3f> GetTraj();

void SaveTraj();

// Tracks the next image using a precomputed depth image.
void TrackImageWithDepth(const cv::Mat& im_left, const cv::Mat& im_depth);

Expand Down
4 changes: 4 additions & 0 deletions modules/matching/lucas_kanade_tracker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,10 @@ void LucasKanadeTracker::SetReferenceImage(const Mat &refIm, const vector<KeyPoi
int mx = (ipoint.x+x) * scaleFactor;
int my = (ipoint.y+y) * scaleFactor;

if (!mask.empty()&(mx < 0 || my < 0 || mx >= mask.cols || my >= mask.rows)){
continue;
}

if(!mask.empty() && mask.at<uchar>(my,mx) == 0){
valid = false;
break;
Expand Down
32 changes: 19 additions & 13 deletions modules/tracking/monocular_map_initializer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,28 +49,34 @@ MonocularMapInitializer::MonocularMapInitializer(Options& options,
internal_status_ = NO_DATA;
}

absl::StatusOr<MonocularMapInitializer::InitializationResults>
MonocularMapInitializer::InitializationResults
MonocularMapInitializer::ProcessNewImage(const cv::Mat& im, const cv::Mat& im_clahe,
const cv::Mat& mask) {
const cv::Mat& mask) {
// Track features and update the feature tracks.
DataAssociation(im, im_clahe, mask);

if (internal_status_ == RECENTLY_RESET) {
return absl::InternalError("Just reset");
MonocularMapInitializer::InitializationResults partial_results;
partial_results.status = absl::InternalError("Just reset");
return partial_results;
}

// Perform optical flow clustering.
auto feature_labels = FeatureTracksClustering();

// Try to perform a rigid initialization.
auto initialization_results_status = RigidInitialization();

if (!initialization_results_status.ok()) {
LOG(INFO) << initialization_results_status.status().message();
return absl::InternalError("Rigid Initialization failed");
}

auto [camera_transform_world, landmarks_positions] = *initialization_results_status;
auto status = initialization_results_status.status;
auto camera_transform_world = initialization_results_status.camera_transform_world;
auto landmarks_positions = initialization_results_status.landmarks_position;

if (!status.ok()) {
LOG(INFO) << status.message();
MonocularMapInitializer::InitializationResults partial_results;
partial_results.camera_transform_world = camera_transform_world;
partial_results.status = absl::InternalError("Rigid Initialization failed");
return partial_results;
}

// Perform a deformable Bundle Adjustment to refine the results.
return InitializationRefinement(current_keypoints_, landmarks_positions, feature_labels, camera_transform_world);
Expand Down Expand Up @@ -224,12 +230,12 @@ MonocularMapInitializer::RigidInitializationResults MonocularMapInitializer::Rig
auto status = rigid_initializer_->Initialize(current_keypoints_, current_keypoint_statuses_,
n_tracks_in_image_, camera_transform_world,
landmarks_position);
RigidInitializationResults result = {status, camera_transform_world, landmarks_position};

if (!status.ok()) {
return absl::InternalError(status.message());
} else {
return make_tuple(camera_transform_world, landmarks_position);
result.landmarks_position.clear(); // Invalidate landmarks on failure
}
return result;
}

MonocularMapInitializer::InitializationResults
Expand Down
12 changes: 7 additions & 5 deletions modules/tracking/monocular_map_initializer.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ class MonocularMapInitializer {
std::shared_ptr<CameraModel> calibration,
std::shared_ptr<ImageVisualizer> image_visualizer);

absl::StatusOr<InitializationResults> ProcessNewImage(const cv::Mat& im, const cv::Mat& im_clahe,
const cv::Mat& mask);
InitializationResults ProcessNewImage(const cv::Mat& im, const cv::Mat& im_clahe,
const cv::Mat& mask);

private:
void DataAssociation(const cv::Mat& im, const cv::Mat& im_clahe,
Expand All @@ -81,9 +81,11 @@ class MonocularMapInitializer {
void ResetInitialization(const cv::Mat& im, const cv::Mat& im_clahe,
const cv::Mat& mask);

typedef absl::StatusOr<
std::tuple<Sophus::SE3f, std::vector<absl::StatusOr<Eigen::Vector3f>>>>
RigidInitializationResults;
struct RigidInitializationResults {
absl::Status status;
Sophus::SE3f camera_transform_world;
std::vector<absl::StatusOr<Eigen::Vector3f>> landmarks_position; // Empty if status not OK
};

RigidInitializationResults RigidInitialization();

Expand Down
17 changes: 13 additions & 4 deletions modules/tracking/tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -95,12 +95,15 @@ void Tracking::TrackImage(const cv::Mat &im, const absl::flat_hash_map<std::stri
PointReuse(im, cv::Mat(), lost_mappoint_ids);

if (current_frame_->GetKeypointsWithStatus({TRACKED_WITH_3D}).size() < 10) {
cout<<"Not enough points to track."<<endl;
exit(0);
}

// KeyFrame insertion.
KeyFrameInsertion(im, masks);

poses.push_back(current_frame_->CameraTransformationWorld());
cout<<"Num poses: "<<poses.size()<<endl;
// Insert frame to the temporal buffer.
map_->SetLastFrame(current_frame_);

Expand All @@ -111,6 +114,10 @@ void Tracking::TrackImage(const cv::Mat &im, const absl::flat_hash_map<std::stri
}
}

std::vector<Sophus::SE3f> Tracking::GetCameraPoses() {
return poses;
}

Tracking::TrackingStatus Tracking::GetTrackingStatus() const {
return tracking_status_;
}
Expand All @@ -137,12 +144,14 @@ void Tracking::MonocularMapInitialization(const cv::Mat& im_left,
const cv::Mat& mask, const cv::Mat& im_clahe) {
auto initialization_status = monocular_map_initializer_->ProcessNewImage(im_left, im_clahe, mask);

if(!initialization_status.ok()) {
LOG(INFO) << initialization_status.status().message();
poses.push_back(initialization_status.camera_transform_world);
cout<<"Num poses: "<<poses.size()<<endl;

if(!initialization_status.status.ok()) {
LOG(INFO) << initialization_status.status.message();
return;
}

auto initialization_results = *initialization_status;
auto initialization_results = initialization_status;

vector<float> depths;
for (int idx = 0; idx < initialization_results.current_keypoints.size(); idx++) {
Expand Down