jeremysalwen / ORB_SLAM_COMMUNITY

A community maintained fork of the inactive ORB_SLAM3 project
GNU General Public License v3.0
14 stars 2 forks source link

camrea poses #2

Open nesquik011 opened 1 month ago

nesquik011 commented 1 month ago

how to get the camera poses ? before and after loop closing

tipodgorsk commented 1 month ago

Hi @nesquik011 !

You should check the result of the System::TrackStereo and System::TrackMonocular (depend if your camera is mono or stereo) functions which return a Sophus::SE3f matrix containing the transform between camera_frame and camera_frame at time 0.

(in case you're using stereo slam, the camera_frame is by convention the camera_left_frame).

If you call the appropriate function in a loop, the estimated pose will be computed and non-stop refreshed (before and after loop closing).

If you want to work with cv::Mat, you should convert this matrix like that (c++ example):

cv::Mat SE3ToCvMat(const Sophus::SE3<float>& se3) {
    // Conversion de la matrice homogène 4x4 en cv::Mat
    const Eigen::Matrix<float, 4, 4> m = se3.matrix();
    cv::Mat cvMat(m.rows(), m.cols(), CV_32F);
    for (int i = 0; i < m.rows(); ++i) {
        for (int j = 0; j < m.cols(); ++j) {
            cvMat.at<float>(i, j) = m(i, j);
        }
    }
    return cvMat;
}

This is surely one of the worst way to do the conversion but it does the job :'(

Hope this helps !

nesquik011 commented 1 month ago

check mapdrawer , @tipodgorsk how it get the camera poses and how it updates the map after loop closering

we need the selected camera poses and after loop closering i want their new poses or update

why the selected poses ? because orb slam dont pick all the frames why after update too ? because they change to be more accurate