UZ-SLAMLab / ORB_SLAM3

ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM
GNU General Public License v3.0
6.49k stars 2.54k forks source link

Wrong rotation #294

Open poetgeorge opened 3 years ago

poetgeorge commented 3 years ago

I use ORBSLAM3 ROS RGBD node with my orbbec rgbd camera and wheeled platform in an indoor envinronment. No external odometry. I run the node on my bags, sometimes when the camera is moving forwards and turning left or right normally, the slam show that it was in purely rotating and lasts for a long time! Some seconds later it creates a new map and continue tracking. My config is the Asus.yaml in Examples/ROS directory

ryleymcc commented 3 years ago

yea i get the same issue with t265 camera

JulioPlaced commented 3 years ago

Did you find a solution? Same issue here, with ROS-Gazebo simulation using RGBD. Sometimes, after turning, SLAM only shows pure rotations until it gets lost and creates a new map. Interestingly, I'm also using a wheeled robot (2D). May this be a ROS-related issue? May this be related to 2D?

hellovuong commented 3 years ago

Hi, For that error in RGB-D, It is caused by all points was considering as far points, more precisely, Depth-Threshold (Far/Close Points) is currently = 0. To solve that issues, reference to #107. Basically, you need to change line 622 in Tracking.cc from if(mSensor==System::STEREO || mSensor==System::IMU_STEREO) to if(mSensor==System::STEREO || mSensor==System::IMU_STEREO || mSensor==System::RGBD) then It should working fine.

JulioPlaced commented 3 years ago

Thanks a lot @hellovuong!!! I knew it was related to the zero value of depth threshold but could not find an easy fix

thomCastillo commented 3 years ago

Could we add depth sensor error as parameter(i.e noise parameter in IMU) to optimization in RGB-D SLAM? If so, how can we add it?

Cheny5863 commented 3 years ago

I use ORBSLAM3 ROS RGBD node with my orbbec rgbd camera and wheeled platform in an indoor envinronment. No external odometry. I run the node on my bags, sometimes when the camera is moving forwards and turning left or right normally, the slam show that it was in purely rotating and lasts for a long time! Some seconds later it creates a new map and continue tracking. My config is the Asus.yaml in Examples/ROS directory

hi bro,had you solved the problem?

Cheny5863 commented 3 years ago

Hi, For that error in RGB-D, It is caused by all points was considering as far points, more precisely, Depth-Threshold (Far/Close Points) is currently = 0. To solve that issues, reference to #107. Basically, you need to change line 622 in Tracking.cc from if(mSensor==System::STEREO || mSensor==System::IMU_STEREO) to if(mSensor==System::STEREO || mSensor==System::IMU_STEREO || mSensor==System::RGBD) then It should working fine.

I did as you said, but there is still a problem