Closed EndlessPeak closed 6 months ago
Hi, I pushed it to this branch https://github.com/hellovuong/stella_vslam/tree/hloc_wip It contained new tracking mode UNSTABLE and require robot model to use it
That's very kind of you,I'm so grateful.
src/stella_vslam/util/geometry.h
is missing,and it's required by src/stella_vslam/tracking_module.cc
. I tried to add geometry.h
by the following code:
#include <Eigen/Geometry>
#include <cmath>
namespace stella_vslam::util::geometry { double get_yaw(const Eigen::Quaterniond& q) { // Convert the quaternion to a 3x3 rotation matrix Eigen::Matrix3d rot_matrix = q.toRotationMatrix();
// Calculate the yaw angle from the rotation matrix.
// atan2 is used to get the angle in the correct quadrant.
double yaw = std::atan2(rot_matrix(1, 0), rot_matrix(0, 0));
return yaw; // Return the yaw angle in radians
}
} // namespace stella_vslam::util::geometry
2. In `tracking_module.cc`, `#include<se3quat.h>` is missing,I guess it is `#include <g2o/types/slam3d/se3quat.h>`?
There is another file missing: src/stella_vslam/optimize/internal/se3/dumb_perspective_factor.h
which is required by src/stella_vslam/optimize/pose_optimizaer_g2o.cc
, I can't infer the details of this file.
I pushed those files, sorry I missed it out
I’m confused because both the hloc branch and the hloc_wip branch aren’t functioning properly. Since hloc_wip is the latest branch, let me describe the issues I encountered on this branch.
The entire program compiles successfully. I added config content in yaml files just like you wrote in openloris folder. The only difference is that I didn't add odometry
part because I don't know the parameters for rgbd tum exactly.
When I run the command ./run_tum_rgdb_slam -d ../../datasets/rgbd_dataset_freiburg2_pioneer_slam -c ../example/tum_rgbd/TUM_RGBD_rgbd_2.yaml --no-sleep
, I encounter a cv::Exception: assertion failed, indicating that there is no image to resize.
Later, after rebuilding with debugging enabled, I discovered that it encounters an assert in the hf_net::compute_global_descriptors
function, specifically at assert(not img.empty());
bool hf_net::compute_global_descriptors(const cv::Mat& img, cv::Mat& globalDescriptors) {
assert(mEngine);
assert(not img.empty());
cv::Mat resizedImg;
cv::resize(img, resizedImg, cv::Size(mInputShape.d[2], mInputShape.d[1]));
// prepare input
Mat2Tensor(resizedImg, input_tensors[0]);
// infer
if (!infer()) {
return false;
}
// get output
GetGlobalDescriptorFromTensor(output_tensors[2], globalDescriptors);
return true;
}
Further investigation led me to the caller hf_net_database::computeRepresentation(const std::shared_ptr<keyframe>& keyframe)
in hf_net_database.cpp
,I added:
void hf_net_database::computeRepresentation(const std::shared_ptr<keyframe>& keyframe) {
assert(not keyframe->img.empty());
hf_net_->compute_global_descriptors(keyframe->img.clone(), keyframe->frm_obs_.global_descriptors_);
}
Despite this, it still triggers the assertion failure, indicating that the keyframe is unable to obtain the image.
But the run_tum_rgbd_slam
should obtain the rgb folder and the depth folder properly,otherwise,it will complain could not load timestamp from folder and throwing std::runtime_error
.
Am I overlooking something?
in this line https://github.com/hellovuong/stella_vslam/blob/ba6a30b65e69172723ff8d405ebfcbf4ccbce018/src/stella_vslam/system.cc#L461
can you change in from
return feed_frame(create_RGBD_frame(rgb_img, depthmap, timestamp, mask, robot_pose, vel), rgb_img);
to:
return feed_frame(create_RGBD_frame(rgb_img.clone(), depthmap, timestamp, mask, robot_pose, vel), rgb_img.clone());
And run in debug mode, then put break point everytime slam create new keyframe to check its image is not empty?
Changing the line 461 don't work.
I found hf_net_database::computeRepresentation(const std::shared_ptr<keyframe>& keyframe)
was finally called by initializer::create_map_for_stereo(data::base_place_recognition* vpr, data::frame& curr_frm)
and this assert will trigger.
bool initializer::create_map_for_stereo(data::base_place_recognition* vpr, data::frame& curr_frm) {
assert(state_ == initializer_state_t::Initializing);
// create an initial keyframe
curr_frm.set_pose_cw(Mat44_t::Identity());
auto curr_keyfrm = data::keyframe::make_keyframe(map_db_->next_keyframe_id_++, curr_frm);
curr_keyfrm->graph_node_->set_spanning_root(curr_keyfrm);
map_db_->add_spanning_root(curr_keyfrm);
assert(not curr_keyfrm->img.empty()); // this assert will trigger
// compute BoW representation
vpr->computeRepresentation(curr_keyfrm);
// add to the map DB
map_db_->add_keyframe(curr_keyfrm);
In keyframe.cc
, seems there has no code for assigning the img
.
std::shared_ptr<keyframe> keyframe::make_keyframe(unsigned int id, const frame& frm) {
auto ptr = std::allocate_shared<keyframe>(Eigen::aligned_allocator<keyframe>(), id, frm);
// covisibility graph node (connections is not assigned yet)
ptr->graph_node_ = stella_vslam::make_unique<graph_node>(ptr);
return ptr;
}
Since the frame does not contain the img
attribute, and the img
is not assigned a value in the data::keyframe::make_keyframe
function, would it make sense to trigger an assert assertion in the initializer?
(Sorry I am poor in using gdb for debugging muti-thread program)
There was a minor issue with the analysis in the final section last night. Now, I believe the problem is as follows: in tracking_module::initialize
, the function initializer_.initialize(camera_->setup_type_, vpr_db_, curr_frm_);
is called.
bool tracking_module::initialize() {
...
// My guess: This initializer will insert keyframe without img assigned
initializer_.initialize(camera_->setup_type_, vpr_db_, curr_frm_);
...
// Now the img is assigned,but it is a litte late.
assert(!is_stopped_keyframe_insertion_);
for (const auto& keyfrm : curr_frm_.ref_keyfrm_->graph_node_->get_keyframes_from_root()) {
// TODO: this trick only works for stereo/rgbd case
keyfrm->img = curr_img_.clone();
mapper_->queue_keyframe(keyfrm);
}
// succeeded
return true;
}
This function invokes create_map_for_stereo(vpr_db, curr_frm);
.
bool initializer::initialize(const camera::setup_type_t setup_type,
data::base_place_recognition* vpr_db, data::frame& curr_frm) {
switch (setup_type) {
...
case camera::setup_type_t::Stereo:
case camera::setup_type_t::RGBD: {
state_ = initializer_state_t::Initializing;
// try to initialize
if (!try_initialize_for_stereo(curr_frm)) {
// failed
return false;
}
// create new map if succeeded
create_map_for_stereo(vpr_db, curr_frm);
break;
}
...
}
Where the keyframe created here does not receive an assignment for img
.
bool initializer::create_map_for_stereo(data::base_place_recognition* vpr, data::frame& curr_frm) {
assert(state_ == initializer_state_t::Initializing);
// create an initial keyframe
curr_frm.set_pose_cw(Mat44_t::Identity());
auto curr_keyfrm = data::keyframe::make_keyframe(map_db_->next_keyframe_id_++, curr_frm);
curr_keyfrm->graph_node_->set_spanning_root(curr_keyfrm);
map_db_->add_spanning_root(curr_keyfrm);
// curr_keyfrm don't have img now.
vpr->computeRepresentation(curr_keyfrm);
After that, the following assignment execute: keyfrm->img = curr_img_.clone();
but it seems a litte late.
Other parts that go through keyframe_inserter::insert_new_keyframe
receive the correct img
assignment.
I've already solved it. Thanks for sharing the code. It helps me a lot.
Hello, sorry to bother you, and thank you for your great work. I noticed that you mentioned in https://github.com/stella-cv/stella_vslam that you would push your local changes, but GitHub still shows your last commit was from last year. Do you have any plans to push your local changes soon?