Skip to content

Commit

Permalink
Move frame::next_id_ to system::next_frame_id_ (#570)
Browse files Browse the repository at this point in the history
  • Loading branch information
ymd-stella authored Feb 25, 2024
1 parent c31d065 commit 96238b7
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 13 deletions.
6 changes: 2 additions & 4 deletions src/stella_vslam/data/frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,9 @@
namespace stella_vslam {
namespace data {

std::atomic<unsigned int> frame::next_id_{0};

frame::frame(const double timestamp, camera::base* camera, feature::orb_params* orb_params,
frame::frame(unsigned int frame_id, const double timestamp, camera::base* camera, feature::orb_params* orb_params,
const frame_observation frm_obs, const std::unordered_map<unsigned int, marker2d>& markers_2d)
: id_(next_id_++), timestamp_(timestamp), camera_(camera), orb_params_(orb_params), frm_obs_(frm_obs),
: id_(frame_id), timestamp_(timestamp), camera_(camera), orb_params_(orb_params), frm_obs_(frm_obs),
markers_2d_(markers_2d),
// Initialize association with 3D points
landmarks_(std::vector<std::shared_ptr<landmark>>(frm_obs_.undist_keypts_.size(), nullptr)) {}
Expand Down
6 changes: 2 additions & 4 deletions src/stella_vslam/data/frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,14 @@ class frame {

/**
* Constructor for monocular frame
* @param frame_id
* @param timestamp
* @param camera
* @param orb_params
* @param frm_obs
* @param markers_2d
*/
frame(const double timestamp, camera::base* camera, feature::orb_params* orb_params,
frame(const unsigned int frame_id, const double timestamp, camera::base* camera, feature::orb_params* orb_params,
const frame_observation frm_obs, const std::unordered_map<unsigned int, marker2d>& markers_2d);

/**
Expand Down Expand Up @@ -162,9 +163,6 @@ class frame {
//! current frame ID
unsigned int id_;

//! next frame ID
static std::atomic<unsigned int> next_id_;

//! timestamp
double timestamp_;

Expand Down
6 changes: 3 additions & 3 deletions src/stella_vslam/system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ data::frame system::create_monocular_frame(const cv::Mat& img, const double time
marker_detector_->detect(img_gray, markers_2d);
}

return data::frame(timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
return data::frame(next_frame_id_++, timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
}

data::frame system::create_stereo_frame(const cv::Mat& left_img, const cv::Mat& right_img, const double timestamp, const cv::Mat& mask) {
Expand Down Expand Up @@ -368,7 +368,7 @@ data::frame system::create_stereo_frame(const cv::Mat& left_img, const cv::Mat&
marker_detector_->detect(img_gray, markers_2d);
}

return data::frame(timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
return data::frame(next_frame_id_++, timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
}

data::frame system::create_RGBD_frame(const cv::Mat& rgb_img, const cv::Mat& depthmap, const double timestamp, const cv::Mat& mask) {
Expand Down Expand Up @@ -430,7 +430,7 @@ data::frame system::create_RGBD_frame(const cv::Mat& rgb_img, const cv::Mat& dep
marker_detector_->detect(img_gray, markers_2d);
}

return data::frame(timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
return data::frame(next_frame_id_++, timestamp, camera_, orb_params_, frm_obs, std::move(markers_2d));
}

std::shared_ptr<Mat44_t> system::feed_monocular_frame(const cv::Mat& img, const double timestamp, const cv::Mat& mask) {
Expand Down
3 changes: 3 additions & 0 deletions src/stella_vslam/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -231,6 +231,9 @@ class system {
//! mapping thread
std::unique_ptr<std::thread> mapping_thread_ = nullptr;

//! next frame ID
std::atomic<unsigned int> next_frame_id_{0};

//! global optimization module
global_optimization_module* global_optimizer_ = nullptr;
//! global optimization thread
Expand Down
2 changes: 0 additions & 2 deletions src/stella_vslam/tracking_module.cc
Original file line number Diff line number Diff line change
Expand Up @@ -105,8 +105,6 @@ void tracking_module::reset() {
bow_db_->clear();
map_db_->clear();

data::frame::next_id_ = 0;

last_reloc_frm_id_ = 0;
last_reloc_frm_timestamp_ = 0.0;

Expand Down

0 comments on commit 96238b7

Please sign in to comment.