ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

rtabmap stereo with original (mono) Bumblebee

asked 2015-06-02 11:41:05 -0600

micah.corah gravatar image

I am trying to set up an original Bumblebee stereo camera with rtabmap. Currently, the issue that I am running into is that stereo_odometry is crashing without giving a discernible error message.

[FATAL] (2015-06-02 12:04:18.939) SensorData.cpp:92::SensorData() Condition (!depthOrRightImage.empty() && _fx>0.0f && _fyOrBaseline>0.0f && _cx>=0.0f && _cy>=0.0f) not met!

*******
FATAL message occurred! Application will now exit.

*******
[stereo_odometry-5] process has died [pid 6850, exit code 1, cmd /opt/ros/hydro/lib/rtabmap_ros/stereo_odometry left/image_rect:=/stereo_camera/left/image_rect right/image_rect:=/stereo_camera/right/image_rect left/camera_info:=/stereo_camera/left/camera_info right/camera_info:=/stereo_camera/right/camera_info odom:=/odometry __name:=stereo_odometry __log:=/home/rockie/.ros/log/3f5c6f20-093f-11e5-a60c-4cbb583a0a1c/stereo_odometry-5.log].
log file: /home/rockie/.ros/log/3f5c6f20-093f-11e5-a60c-4cbb583a0a1c/stereo_odometry-5*.log

Relevant parts of my launch file look like:

Camera:

<launch>
  <node pkg="camera1394stereo" type="camera1394stereo_node" name="camera1394stereo_node" output="screen" >
    <param name="video_mode" value="1024x768_mono16" />
    <param name="format7_color_coding" value="raw16" />
    <param name="bayer_pattern" value="" />
    <param name="bayer_method" value="" />
    <param name="stereo_method" value="Interlaced" />
    <param name="camera_info_url_left" value="file://$(find stereo_slam)/config/cal_left.yaml" />
    <param name="camera_info_url_right" value="file://$(find stereo_slam)/config/cal_right.yaml" />
  </node>
</launch>

Rectification:

 <!-- Run the ROS package stereo_image_proc for image rectification -->
  <group ns="/stereo_camera" >
    <node pkg="nodelet" type="nodelet" name="stereo_nodelet"  args="manager"/>

    <node pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc">
      <param name="disparity_range" value="128"/>
    </node>
  </group>

Transform:

  <arg name="pi/2" value="1.5707963267948966" />
  <arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
  <node pkg="tf" type="static_transform_publisher" name="camera_base_link"
    args="$(arg optical_rotate) base_link stereo_camera 100" />

Odometry:

   <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen" >
      <remap from="left/image_rect"       to="/stereo_camera/left/image_rect"/>
      <remap from="right/image_rect"      to="/stereo_camera/right/image_rect"/>
      <remap from="left/camera_info"      to="/stereo_camera/left/camera_info"/>
      <remap from="right/camera_info"     to="/stereo_camera/right/camera_info"/>
      <remap from="odom"                  to="/odometry"/>

      <param name="frame_id" type="string" value="base_link"/>
      <param name="odom_frame_id" type="string" value="odom"/>

      <param name="Odom/InlierDistance" type="string" value="0.1"/>
      <param name="Odom/MinInliers" type="string" value="10"/>
      <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
      <param name="Odom/MaxDepth" type="string" value="10"/>
      <param name="OdomBow/NNDR" type="string" value="0.8"/>

      <param name="GFTT/MaxCorners" type="string" value="500"/>
      <param name="GFTT/MinDistance" type="string" value="5"/>

      <param name="Odom/FillInfoData" type="string" value="true"/>
   </node>

Any ideas what my issue could be?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2015-06-03 13:01:27 -0600

micah.corah gravatar image

The issue was that the left and right cameras were switched. Remapping each side in camera1394stereo fixed the problem. Rtab-map in Indigo warns that the baseline is negative which tipped me off.

edit flag offensive delete link more
0

answered 2015-06-03 12:24:15 -0600

matlabbe gravatar image

updated 2015-06-03 12:25:00 -0600

The fatal error:

(!depthOrRightImage.empty() && _fx>0.0f && _fyOrBaseline>0.0f && _cx>=0.0f && _cy>=0.0f) not met!

tells that the right image is empty, the focal length is null or the baseline is null. Things to check:

  1. "/stereo_camera/right/image_rect" is okay? $ rqt_image_view /stereo_camera/right/image_rect
  2. left and right camera infos contain valid calibration values (particularly left fx and right Tx). Example (note Tx=-58.3626989865376 for right P(0,3)):
$ rostopic echo /stereo_camera/left/camera_info
header: 
  seq: 1384
  stamp: 
    secs: 1415737789
    nsecs: 373433828
  frame_id: stereo_camera
height: 480
width: 640
distortion_model: plumb_bob
D: [-0.344858300062205, 0.131731614744127, -0.00032220157418798, -0.000178643627395838, 0.0]
K: [520.84106910681, 0.0, 320.207922533597, 0.0, 520.652683004955, 251.69140630101, 0.0, 0.0, 1.0]
R: [0.999977409119708, -0.00542294021453702, -0.00397151981806852, 0.00542696944573559, 0.999984769417176, 0.00100445821860056, 0.00396601221263954, -0.00102598884371095, 0.999991609011807]
P: [487.608731712861, 0.0, 318.1162109375, 0.0, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 1
binning_y: 1
roi: 
  x_offset: 0
  y_offset: 0
  height: 480
  width: 640
  do_rectify: False

$ rostopic echo /stereo_camera/right/camera_info
header: 
  seq: 2740
  stamp: 
    secs: 1415737874
    nsecs: 113634825
  frame_id: stereo_camera
height: 480
width: 640
distortion_model: plumb_bob
D: [-0.350198880846778, 0.143262162037345, -0.000540958577710845, -0.000386869942974346, 0.0]
K: [525.042672813, 0.0, 315.778978739153, 0.0, 524.605377865008, 246.116481979902, 0.0, 0.0, 1.0]
R: [0.999991166299663, -0.00384047779504094, 0.00170823094047773, 0.00384221006573169, 0.999992106658553, -0.00101194980141688, -0.0017043310860856, 0.0010185042442697, 0.999998028950384]
P: [487.608731712861, 0.0, 318.1162109375, -58.3626989865376, 0.0, 487.608731712861, 249.44425201416, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 1
binning_y: 1
roi: 
  x_offset: 0
  y_offset: 0
  height: 480
  width: 640
  do_rectify: False
edit flag offensive delete link more

Comments

I didn't get to updating earlier. Turns out that the left and right of the camera were switched. rtab-map in hydro does not give meaningful output for this. On indigo it warns that the baseline is negative.

micah.corah gravatar image micah.corah  ( 2015-06-03 12:58:56 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2015-06-02 11:41:05 -0600

Seen: 549 times

Last updated: Jun 03 '15