Open dubing-bit opened 2 months ago
OrbSlam::OrbSlam(const VisualSlamSettings::Ptr &vslam_set, const CameraSettings::Ptr &cam_set, const ImuSettings::Ptr &imu_set)
: m_prev_keyid(-1),
m_slam_setting((*vslam_set)["slam_setting"].toDouble()),
m_resizing((*vslam_set)["resizing"].toDouble()),
m_timestamp_reference(0),
m_path_vocabulary((*vslam_set)["path_vocabulary"].toString())
{
// Read the settings files
m_slam = new ORB_SLAM::System(m_path_vocabulary, m_slam_setting, ORB_SLAM::System::MONOCULAR,false);
//namespace ph = std::placeholders;
//std::function<void(ORB_SLAM2::KeyFrame*)> kf_update = std::bind(&OrbSlam::keyframeUpdateCb, this, ph::_1);
//_slam->RegisterKeyTransport(kf_update);
}
OrbSlam::~OrbSlam()
{
m_slam->Shutdown();
delete m_slam;
}
VisualSlamIF::State OrbSlam::track(Frame::Ptr &frame, const cv::Mat &T_c2w_initial)
{
if (m_timestamp_reference == 0)
{
//Sophus::SE3f Tse1 = m_slam->TrackMonocular(frame->getImageRaw(), m_timestamp_reference, m_imu_queue);
m_timestamp_reference = frame->getTimestamp();
return State::LOST;
}
// Set image resizing accoring to settings
// frame->setImageResizeFactor(m_resizing);
double timestamp = static_cast<double>(frame->getTimestamp() - m_timestamp_reference)/10e3;
LOG_IF_F(INFO, true, "Time elapsed since first frame: %4.2f [s]", timestamp);
// ORB SLAM returns a transformation from the world to the camera frame (T_w2c). In case we provide an initial guess
// of the current pose, we have to invert this before, because in OpenREALM the standard is defined as T_c2w.
Sophus::SE3f Tse3 = m_slam->TrackMonocular(frame->getImageRaw(),timestamp);
int TrackingState = m_slam->GetTrackingState();
LOG_F(INFO,"TrackState is %u",TrackingState);
if (!Tse3.rotationMatrix().isApprox(Eigen::Matrix3f::Identity()) || !Tse3.translation().isApprox(Eigen::Vector3f::Zero())){
cv::Mat T_w2c = SE32Mat(Tse3);
cv::Mat T_c2w = invertPose(T_w2c);
T_c2w.convertTo(T_c2w, CV_64F);
T_c2w.pop_back();
frame->setVisualPose(T_c2w);
//std::cout << "Soll:\n" << T_c2w << std::endl;
//std::cout << "Schätz:\n" << T_c2w_initial << std::endl;
frame->setSparseCloud(getTrackedMapPoints(), true);
auto keyid = static_cast<int32_t>(m_slam->GetLastKeyFrameId());
if (m_prev_keyid == -1)
{
m_prev_keyid = keyid;
return State::INITIALIZED;
}
else if (m_prev_keyid != keyid)
{
m_prev_keyid = keyid;
m_orb_to_frame_ids.insert({keyid, frame->getFrameId()});
return State::KEYFRAME_INSERT;
}
else
{
return State::FRAME_INSERT;
}
}
return State::LOST;
}
Eigen::Vector3f wp = mappoints[i]->GetWorldPos();
cv::Mat p = (cv::Mat_<float>(3, 1) << wp(0), wp(1), wp(2));
points.push_back(p);
I tried to use deep learning feature detection method to replace ORB,based on ORB-SLAM3 the modification was done and is tested feasible. I tried to compile OpenREALM using the modified ORB-SLAM3. the compilation process was smooth, including Openrealm and OpenREALM_ROS1_Bridge. unfortunately, no results were produced at the end. I think it's the SLAM used in Openrealm that is replaceable, but from compilation experience, it's usually easier to compile successfully using your RepositoriesSLAM libraries (including ORB-SLAM3 https://github.com/laxnpander/ORB_SLAM3 and OpenVSLAM [https://github.com/laxnpander/openvslam]() ). Is there anything I should be concerned of when using other SLAM libraries?