appliedAI-Initiative/orb_slam_2_ros

Failed to get camera calibration parameters for orb_slam2_r200_stereo

jedichen121 opened this issue · 3 comments

I was testing this repository following the approach listed here: using turtlebot3_gazebo with r200. When using orb_slam2_r200_stereo.launch, it showed the following errors:

NODES
  /
    orb_slam2_stereo (orb_slam2_ros/orb_slam2_ros_stereo)

ROS_MASTER_URI=http://localhost:11311

process[orb_slam2_stereo-1]: started with pid [352344]
[ERROR] [1620161439.618458932]: Failed to get camera calibration parameters from the launch file.
terminate called after throwing an instance of 'std::runtime_error'
  what():  No cam calibration
[orb_slam2_stereo-1] process has died [pid 352344, exit code -6, cmd /home/jedi/catkin_ws/devel/lib/orb_slam2_ros/orb_slam2_ros_stereo image_left/image_color_rect:=/cam_front/left/image_rect_color image_right/image_color_rect:=/cam_front/right/image_rect_color __name:=orb_slam2_stereo __log:=/home/jedi/.ros/log/7d3dc3d8-ad18-11eb-a2af-5076af2f9e4b/orb_slam2_stereo-1.log].
log file: /home/jedi/.ros/log/7d3dc3d8-ad18-11eb-a2af-5076af2f9e4b/orb_slam2_stereo-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete

I tried to check the log file orb_slam2_stereo-1.log but it didn't exist in that path. Only orb_slam2_r200_mono.launch can work to some extend, but I was not able to show the point cloud.

Screenshot from 2021-05-04 22-50-21

Any suggestion on how to solve this? Thank you.

Same issue here

same issue too
R200 camera (real, no simulator), that part in the error that say "cam_front" looks weird because if you change the camera info topic in the stereo_node.cc and set get the calibration from the camera to true, it always ask by
process[orb_slam2_stereo-1]: started with pid [5715] [ INFO] [1620784342.455007438]: Listening for camera info on topic /image_left/camera_info .
R200 stereo node has a issue i think, also the launch looks mixed with other's camera one probably zed

With rgbd node didnt work too, the launch didn't worked, didn't get the launch calibration, sending this

`ROS_MASTER_URI=http://localhost:11311

process[orb_slam2_rgbd-1]: started with pid [14813]
[ERROR] [1620777130.183668596]: Failed to get camera calibration parameters from the launch file.
terminate called after throwing an instance of 'std::runtime_error'
what(): No cam calibration
[orb_slam2_rgbd-1] process has died [pid 14813, exit code -6, cmd /home/nx/orb_slam2_ws/devel/lib/orb_slam2_ros/orb_slam2_ros_rgbd /camera/rgb/image_raw:=/camera/rgb/image_rect_color /camera/depth_registered/image_raw:=/camera/depth_registered/sw_registered/image_rect __name:=orb_slam2_rgbd __log:=/home/nx/.ros/log/f9506674-b2ae-11eb-a2a4-70665530bc9f/orb_slam2_rgbd-1.log].
log file: /home/nx/.ros/log/f9506674-b2ae-11eb-a2a4-70665530bc9f/orb_slam2_rgbd-1*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
`
if I set the parameter true from false (default)

New map created with 16 points [ WARN] [1620777400.925992631]: Could not find a connection between 'camera_link' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees. [ WARN] [1620777400.928075272]: Could not find a connection between 'camera_link' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees.
the launch topics are wrong too. I could make it work fixing the topics, getting calibration from the camera and adding TFs to complete the tree.
this r200 camera info topic, will orbslam2 get the calibration properly?

this rgbd for r200 works for me, but not sure if calibration from the camera is imported properly..

<launch>
  <node name="orb_slam2_rgbd" pkg="orb_slam2_ros"
      type="orb_slam2_ros_rgbd" output="screen">

       <remap from="/camera/rgb/image_raw" to="/camera/rgb/image_rect_color" />
       <remap from="/camera/depth_registered/image_raw" to="/camera/depth_registered/sw_registered/image_rect" />

       <param name="publish_pointcloud" type="bool" value="true" />
       <param name="publish_pose" type="bool" value="true" />
       <param name="localize_only" type="bool" value="false" />
       <param name="reset_map" type="bool" value="false" />

       <!-- static parameters -->
       <param name="load_map" type="bool" value="false" />
       <param name="map_file" type="string" value="map.bin" />
       <param name="voc_file" type="string" value="$(find orb_slam2_ros)/orb_slam2/Vocabulary/ORBvoc.txt" />

       <param name="pointcloud_frame_id" type="string" value="map" />
       <param name="camera_frame_id" type="string" value="camera_link" />
       <param name="min_num_kf_in_map" type="int" value="5" />

       <!-- ORB parameters -->
       <param name="/ORBextractor/nFeatures" type="int" value="1000" />
       <param name="/ORBextractor/scaleFactor" type="double" value="1.2" />
       <param name="/ORBextractor/nLevels" type="int" value="8" />
       <param name="/ORBextractor/iniThFAST" type="int" value="20" />
       <param name="/ORBextractor/minThFAST" type="int" value="7" />

       <!-- Camera parameters -->
       <!-- Camera frames per second -->
       <param name="camera_fps" type="int" value="30" />
       <!-- Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) -->
       <param name="camera_rgb_encoding" type="bool" value="true" />
       <!-- Close/Far threshold. Baseline times. -->
       <param name="ThDepth" type="double" value="40.0" />
       <!-- Deptmap values factor (what pixel value in the depth image corresponds to 1m) -->
       <param name="depth_map_factor" type="double" value="1.0" />

        <!-- Camera calibration parameters -->
        <!--If the node should wait for a camera_info topic to take the camera calibration data-->
       <param name="load_calibration_from_cam" type="bool" value="true" />
       <!-- Camera calibration and distortion parameters (OpenCV) -->
      <param name="camera_fx" type="double" value="632.7927856445312" />
      <param name="camera_fy" type="double" value="626.8605346679688" />
      <param name="camera_cx" type="double" value="311.43603515625" />
      <param name="camera_cy" type="double" value="248.0950164794922" />
       <!-- Camera calibration and distortion parameters (OpenCV) -->
      <param name="camera_k1" type="double" value="-0.09097914397716522" />
      <param name="camera_k2" type="double" value="0.06503549218177795" />
      <param name="camera_p1" type="double" value="0.000849052332341671" />
      <param name="camera_p2" type="double" value="0.001785792293958366" />
      <!-- IR projector baseline times fx (aprox.) -->
      <param name="camera_baseline" type="double" value="37.2925" />
  </node>
  <node pkg="tf" type="static_transform_publisher" name="base_link_to_camera_link" args="0 0 0 0 0 0 base_link camera_link 100" />
</launch>

I think is better change base_link by base_frame, it is more apropiate as orb_slam2 is used as vio backend in other softwares that commonly use base_frame, lidars manufacturers and UDRF use base_frame and laser_frame more than base_link.
thanks!! you made a great orbslam2 setup, the best for sure

same issue too R200 camera (real, no simulator), that part in the error that say "cam_front" looks weird because if you change the camera info topic in the stereo_node.cc and set get the calibration from the camera to true, it always ask by process[orb_slam2_stereo-1]: started with pid [5715] [ INFO] [1620784342.455007438]: Listening for camera info on topic /image_left/camera_info . R200 stereo node has a issue i think, also the launch looks mixed with other's camera one probably zed

With rgbd node didnt work too, the launch didn't worked, didn't get the launch calibration, sending this

`ROS_MASTER_URI=http://localhost:11311

process[orb_slam2_rgbd-1]: started with pid [14813] [ERROR] [1620777130.183668596]: Failed to get camera calibration parameters from the launch file. terminate called after throwing an instance of 'std::runtime_error' what(): No cam calibration [orb_slam2_rgbd-1] process has died [pid 14813, exit code -6, cmd /home/nx/orb_slam2_ws/devel/lib/orb_slam2_ros/orb_slam2_ros_rgbd /camera/rgb/image_raw:=/camera/rgb/image_rect_color /camera/depth_registered/image_raw:=/camera/depth_registered/sw_registered/image_rect __name:=orb_slam2_rgbd __log:=/home/nx/.ros/log/f9506674-b2ae-11eb-a2a4-70665530bc9f/orb_slam2_rgbd-1.log]. log file: /home/nx/.ros/log/f9506674-b2ae-11eb-a2a4-70665530bc9f/orb_slam2_rgbd-1*.log all processes on machine have died, roslaunch will exit shutting down processing monitor... ... shutting down processing monitor complete if I set the parameter true from false (default)New map created with 16 points [ WARN] [1620777400.925992631]: Could not find a connection between 'camera_link' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees. [ WARN] [1620777400.928075272]: Could not find a connection between 'camera_link' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees. `
the launch topics are wrong too. I could make it work fixing the topics, getting calibration from the camera and adding TFs to complete the tree.
this r200 camera info topic, will orbslam2 get the calibration properly?

this rgbd for r200 works for me, but not sure if calibration from the camera is imported properly..

<launch>
  <node name="orb_slam2_rgbd" pkg="orb_slam2_ros"
      type="orb_slam2_ros_rgbd" output="screen">

       <remap from="/camera/rgb/image_raw" to="/camera/rgb/image_rect_color" />
       <remap from="/camera/depth_registered/image_raw" to="/camera/depth_registered/sw_registered/image_rect" />

       <param name="publish_pointcloud" type="bool" value="true" />
       <param name="publish_pose" type="bool" value="true" />
       <param name="localize_only" type="bool" value="false" />
       <param name="reset_map" type="bool" value="false" />

       <!-- static parameters -->
       <param name="load_map" type="bool" value="false" />
       <param name="map_file" type="string" value="map.bin" />
       <param name="voc_file" type="string" value="$(find orb_slam2_ros)/orb_slam2/Vocabulary/ORBvoc.txt" />

       <param name="pointcloud_frame_id" type="string" value="map" />
       <param name="camera_frame_id" type="string" value="camera_link" />
       <param name="min_num_kf_in_map" type="int" value="5" />

       <!-- ORB parameters -->
       <param name="/ORBextractor/nFeatures" type="int" value="1000" />
       <param name="/ORBextractor/scaleFactor" type="double" value="1.2" />
       <param name="/ORBextractor/nLevels" type="int" value="8" />
       <param name="/ORBextractor/iniThFAST" type="int" value="20" />
       <param name="/ORBextractor/minThFAST" type="int" value="7" />

       <!-- Camera parameters -->
       <!-- Camera frames per second -->
       <param name="camera_fps" type="int" value="30" />
       <!-- Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) -->
       <param name="camera_rgb_encoding" type="bool" value="true" />
       <!-- Close/Far threshold. Baseline times. -->
       <param name="ThDepth" type="double" value="40.0" />
       <!-- Deptmap values factor (what pixel value in the depth image corresponds to 1m) -->
       <param name="depth_map_factor" type="double" value="1.0" />

        <!-- Camera calibration parameters -->
        <!--If the node should wait for a camera_info topic to take the camera calibration data-->
       <param name="load_calibration_from_cam" type="bool" value="true" />
       <!-- Camera calibration and distortion parameters (OpenCV) -->
      <param name="camera_fx" type="double" value="632.7927856445312" />
      <param name="camera_fy" type="double" value="626.8605346679688" />
      <param name="camera_cx" type="double" value="311.43603515625" />
      <param name="camera_cy" type="double" value="248.0950164794922" />
       <!-- Camera calibration and distortion parameters (OpenCV) -->
      <param name="camera_k1" type="double" value="-0.09097914397716522" />
      <param name="camera_k2" type="double" value="0.06503549218177795" />
      <param name="camera_p1" type="double" value="0.000849052332341671" />
      <param name="camera_p2" type="double" value="0.001785792293958366" />
      <!-- IR projector baseline times fx (aprox.) -->
      <param name="camera_baseline" type="double" value="37.2925" />
  </node>
  <node pkg="tf" type="static_transform_publisher" name="base_link_to_camera_link" args="0 0 0 0 0 0 base_link camera_link 100" />
</launch>

I think is better change base_link by base_frame, it is more apropiate as orb_slam2 is used as vio backend in other softwares that commonly use base_frame, lidars manufacturers and UDRF use base_frame and laser_frame more than base_link. thanks!! you made a great orbslam2 setup, the best for sure

Thank you for sharing your launch file. Have you tried visualizing camera data in Rviz after this?