NVIDIA-ISAAC-ROS / isaac_ros_visual_slam

Visual SLAM/odometry package based on NVIDIA-accelerated cuVSLAM
https://developer.nvidia.com/isaac-ros-gems
Apache License 2.0
867 stars 139 forks source link

some basic questions #5

Closed FPSychotic closed 2 years ago

FPSychotic commented 2 years ago

1-Hi, is it "odom" TF static against "base_link_somooth/rectified" TFs, like could be "map" TF compared with "camera_link" in realsenses?.

2-Can both TFs "base_link_somooth/rectified" be published simultaneosly working? I mean will activate the rectified disconnect the smooth?

3-the odometry topic /visual_odometry/tf_stamped refer always to base_link_smooth TF?

4- recitified always appear in my my TF tree in Rviz2 even set in false, is this correct?

5- rectified include or means with loop closure?

thanks by share it is a great peace of software, smart people

swapnesh-wani commented 2 years ago

Hello @FPSychotic, Thank you for using our visual odometry package.

  1. is it "odom" TF static against "base_link_smooth/rectified" TFs, like could be "map" TF compared with "camera_link" in realsenses?

Yes, the "odom" frame is a fixed frame(it won't change over time). We follow ROS-REP-105 for the functionality of a frame and its naming. "base_link_smooth" and "base_link_rectified" are the frames where the current camera pose is reported.

  1. Can both TFs "base_link_smooth/rectified" be published simultaneously working?

Yes, both modes can be used simultaneously. "base_link_smooth" will always get published irrespectively.

  1. the odometry topic /visual_odometry/tf_stamped refer always to base_link_smooth TF?

No, it can refer to both the transforms. Please see the msg details.

  1. rectified always appears in my TF tree in Rviz2 even set in false, is this correct?

If enable_rectified_pose is set to false, it will publish the base_link_smooth pose in base_link_rectified.

  1. rectified include or means with loop closure?

Yes, it uses loop closure.

FPSychotic commented 2 years ago

Thanks by your fast answer and amazing job. Las question: Am I right thinking that in case of both base_link are active the odometry topic refer to the rectified one? . Just show you how good your package works. In only VIO and applied to SLAM in RVIZ2 onboard as I didn't use the standard installation as I didn't use docker. Low and very low light condition. https://youtu.be/V2Gz6kAzCzY https://youtu.be/FWPwGUXdsIs

swapnesh-wani commented 2 years ago

Am I right thinking that in case of both base_link are active the odometry topic refers to the rectified one?

visual_odometry/tf_stamped topic will always report both the rectified_transform and smooth_transform. In case of enable_rectified_pose = false, rectified_transform will be equal to smooth_transform. And, in case of enable_rectified_pose = true, rectified_transform will report pose from loop closure and smooth_transform will report pose from pure visual odometry.