rtabmap stereo with original (mono) Bumblebee
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?