Skip to content

Commit

Permalink
Add update_pose() API call (#79)
Browse files Browse the repository at this point in the history
* Add update_pose() API call

* Meet review items

* Update src/openvslam/tracking_module.cc

Co-authored-by: ymd-stella <[email protected]>

* Improve the code

* Remove unnecessary if-statement

* Docs update, variables rename and other changes

Co-authored-by: ymd-stella <[email protected]>
  • Loading branch information
AlexeyMerzlyakov and ymd-stella authored May 29, 2021
1 parent 35c1230 commit 10b23ae
Show file tree
Hide file tree
Showing 9 changed files with 157 additions and 3 deletions.
10 changes: 7 additions & 3 deletions docs/parameters.rst
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@ PangolinViewer

.. _section-parameters-others:

Others
======
Tracker
=======

.. list-table::
:header-rows: 1
Expand All @@ -154,6 +154,10 @@ Others
* - Name
- Description
* - depth_threshold
- The ratio used to determine the depth threshold
- The ratio used to determine the depth threshold.
* - depthmap_factor
- The ratio used to convert depth image pixel values to distance.
* - reloc_distance_threshold
- Maximum distance threshold (in meters) where close keyframes could be found when doing a relocalization by pose.
* - reloc_angle_threshold
- Maximum angle threshold (in radians) between given pose and close keyframes when doing a relocalization by pose.
28 changes: 28 additions & 0 deletions src/openvslam/data/map_database.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,34 @@ std::vector<keyframe*> map_database::get_all_keyframes() const {
return keyframes;
}

std::vector<keyframe*> map_database::get_close_keyframes(const Mat44_t& pose,
const double distance_threshold,
const double angle_threshold) const {
std::lock_guard<std::mutex> lock(mtx_map_access_);

// Close (within given thresholds) keyframes
std::vector<keyframe*> filtered_keyframes;

const double cos_angle_threshold = std::cos(angle_threshold);

// Calculate angles and distances between given pose and all keyframes
Mat33_t M = pose.block<3, 3>(0, 0);
Vec3_t Mt = pose.block<3, 1>(0, 3);
for (const auto id_keyframe : keyframes_) {
Mat33_t N = id_keyframe.second->get_cam_pose().block<3, 3>(0, 0);
Vec3_t Nt = id_keyframe.second->get_cam_pose().block<3, 1>(0, 3);
// Angle between two cameras related to given pose and selected keyframe
const double cos_angle = ((M * N.transpose()).trace() - 1) / 2;
// Distance between given pose and selected keyframe
const double dist = (Nt - Mt).norm();
if (dist < distance_threshold && cos_angle > cos_angle_threshold) {
filtered_keyframes.push_back(id_keyframe.second);
}
}

return filtered_keyframes;
}

unsigned int map_database::get_num_keyframes() const {
std::lock_guard<std::mutex> lock(mtx_map_access_);
return keyframes_.size();
Expand Down
11 changes: 11 additions & 0 deletions src/openvslam/data/map_database.h
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,17 @@ class map_database {
*/
std::vector<keyframe*> get_all_keyframes() const;

/**
* Get closest keyframes to a given pose
* @param pose Given pose
* @param distance_threshold Maximum distance where close keyframes could be found
* @param angle_threshold Maximum angle between given pose and close keyframes
* @return Vector closest keyframes
*/
std::vector<keyframe*> get_close_keyframes(const Mat44_t& pose,
const double distance_threshold,
const double angle_threshold) const;

/**
* Get the number of keyframes
* @return
Expand Down
6 changes: 6 additions & 0 deletions src/openvslam/module/relocalizer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,12 @@ bool relocalizer::relocalize(data::frame& curr_frm) {
if (reloc_candidates.empty()) {
return false;
}

return reloc_by_candidates(curr_frm, reloc_candidates);
}

bool relocalizer::reloc_by_candidates(data::frame& curr_frm,
const std::vector<openvslam::data::keyframe*>& reloc_candidates) {
const auto num_candidates = reloc_candidates.size();

std::vector<std::vector<data::landmark*>> matched_landmarks(num_candidates);
Expand Down
4 changes: 4 additions & 0 deletions src/openvslam/module/relocalizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,10 @@ class relocalizer {
//! Relocalize the specified frame
bool relocalize(data::frame& curr_frm);

//! Relocalize the specified frame by given candidates list
bool reloc_by_candidates(data::frame& curr_frm,
const std::vector<openvslam::data::keyframe*>& reloc_candidates);

private:
//! Extract valid (non-deleted) landmarks from landmark vector
std::vector<unsigned int> extract_valid_indices(const std::vector<data::landmark*>& landmarks) const;
Expand Down
11 changes: 11 additions & 0 deletions src/openvslam/system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -286,6 +286,17 @@ std::shared_ptr<Mat44_t> system::feed_RGBD_frame(const cv::Mat& rgb_img, const c
return cam_pose_wc;
}

bool system::update_pose(const Mat44_t& pose) {
bool status = tracker_->request_update_pose(pose);
if (status) {
// Even if state will be lost, still update the pose in map_publisher_
// to clearly show new camera position
map_publisher_->set_current_cam_pose(pose);
map_publisher_->set_current_cam_pose_wc(pose.inverse());
}
return status;
}

void system::pause_tracker() {
tracker_->request_pause();
}
Expand Down
7 changes: 7 additions & 0 deletions src/openvslam/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,13 @@ class system {
//! (Note: RGB and Depth images must be aligned)
std::shared_ptr<Mat44_t> feed_RGBD_frame(const cv::Mat& rgb_img, const cv::Mat& depthmap, const double timestamp, const cv::Mat& mask = cv::Mat{});

//-----------------------------------------
// pose initializing/updating

//! Request to update the pose to a given one.
//! Return failure in case if previous request was not finished.
bool update_pose(const Mat44_t& pose);

//-----------------------------------------
// management for pause

Expand Down
62 changes: 62 additions & 0 deletions src/openvslam/tracking_module.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,17 @@ double get_depthmap_factor(const camera::base* camera, const YAML::Node& yaml_no
}
return depthmap_factor;
}

double get_reloc_distance_threshold(const YAML::Node& yaml_node) {
spdlog::debug("load maximum distance threshold where close keyframes could be found");
return yaml_node["reloc_distance_threshold"].as<double>(0.2);
}

double get_reloc_angle_threshold(const YAML::Node& yaml_node) {
spdlog::debug("load maximum angle threshold between given pose and close keyframes");
return yaml_node["reloc_angle_threshold"].as<double>(0.45);
}

} // unnamed namespace

namespace openvslam {
Expand All @@ -61,6 +72,8 @@ tracking_module::tracking_module(const std::shared_ptr<config>& cfg, system* sys
data::bow_vocabulary* bow_vocab, data::bow_database* bow_db)
: camera_(cfg->camera_), true_depth_thr_(get_true_depth_thr(camera_, cfg->yaml_node_)),
depthmap_factor_(get_depthmap_factor(camera_, cfg->yaml_node_)),
reloc_distance_threshold_(get_reloc_distance_threshold(cfg->yaml_node_)),
reloc_angle_threshold_(get_reloc_angle_threshold(cfg->yaml_node_)),
system_(system), map_db_(map_db), bow_vocab_(bow_vocab), bow_db_(bow_db),
initializer_(cfg->camera_->setup_type_, map_db, bow_db, util::yaml_optional_ref(cfg->yaml_node_, "Initializer")),
frame_tracker_(camera_, 10), relocalizer_(bow_db_), pose_optimizer_(),
Expand Down Expand Up @@ -191,6 +204,32 @@ std::shared_ptr<Mat44_t> tracking_module::track_RGBD_image(const cv::Mat& img, c
return cam_pose_wc;
}

bool tracking_module::request_update_pose(const Mat44_t& pose) {
std::lock_guard<std::mutex> lock(mtx_update_pose_request_);
if (update_pose_is_requested_) {
spdlog::warn("Can not process new pose update request while previous was not finished");
return false;
}
update_pose_is_requested_ = true;
requested_pose_ = pose;
return true;
}

bool tracking_module::update_pose_is_requested() {
std::lock_guard<std::mutex> lock(mtx_update_pose_request_);
return update_pose_is_requested_;
}

Mat44_t& tracking_module::get_requested_pose() {
std::lock_guard<std::mutex> lock(mtx_update_pose_request_);
return requested_pose_;
}

void tracking_module::finish_update_pose_request() {
std::lock_guard<std::mutex> lock(mtx_update_pose_request_);
update_pose_is_requested_ = false;
}

void tracking_module::reset() {
spdlog::info("resetting system");

Expand Down Expand Up @@ -333,6 +372,28 @@ bool tracking_module::initialize() {

bool tracking_module::track_current_frame() {
bool succeeded = false;

if (update_pose_is_requested()) {
// Force relocalization by pose
curr_frm_.set_cam_pose(get_requested_pose());

curr_frm_.compute_bow();
const auto candidates = map_db_->get_close_keyframes(get_requested_pose(),
reloc_distance_threshold_,
reloc_angle_threshold_);
if (!candidates.empty()) {
succeeded = relocalizer_.reloc_by_candidates(curr_frm_, candidates);
if (succeeded) {
last_reloc_frm_id_ = curr_frm_.id_;
}
}
else {
curr_frm_.cam_pose_cw_is_valid_ = false;
}
finish_update_pose_request();
return succeeded;
}

if (tracking_state_ == tracker_state_t::Tracking) {
// Tracking mode
if (velocity_is_valid_ && last_reloc_frm_id_ + 2 < curr_frm_.id_) {
Expand All @@ -354,6 +415,7 @@ bool tracking_module::track_current_frame() {
last_reloc_frm_id_ = curr_frm_.id_;
}
}

return succeeded;
}

Expand Down
21 changes: 21 additions & 0 deletions src/openvslam/tracking_module.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,10 @@ class tracking_module {
//! (Note: RGB and Depth images must be aligned)
std::shared_ptr<Mat44_t> track_RGBD_image(const cv::Mat& img, const cv::Mat& depthmap, const double timestamp, const cv::Mat& mask = cv::Mat{});

//! Request to update the pose to a given one.
//! Return failure in case if previous request was not finished yet.
bool request_update_pose(const Mat44_t& pose);

//-----------------------------------------
// management for reset process

Expand Down Expand Up @@ -113,6 +117,10 @@ class tracking_module {
//! depthmap factor (pixel_value / depthmap_factor = true_depth)
double depthmap_factor_ = 1.0;

//! closest keyframes thresholds (by distance and angle) to relocalize with when updating by pose
double reloc_distance_threshold_ = 0.2;
double reloc_angle_threshold_ = 0.45;

//-----------------------------------------
// variables

Expand Down Expand Up @@ -253,6 +261,19 @@ class tracking_module {

//! Pause of the tracking module is requested or not
bool pause_is_requested_ = false;

//! Mutex for update pose request into given position
mutable std::mutex mtx_update_pose_request_;
//! Update into a given position is requested or not
bool update_pose_is_requested();
//! Get requested for relocalization pose
Mat44_t& get_requested_pose();
//! Finish update request. Returns true in case of request was made.
void finish_update_pose_request();
//! Indicator of update pose request
bool update_pose_is_requested_ = false;
//! Requested pose to update
Mat44_t requested_pose_;
};

} // namespace openvslam
Expand Down

0 comments on commit 10b23ae

Please sign in to comment.