introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.75k stars 785 forks source link

camera initialization error #106

Closed AndreV84 closed 7 years ago

AndreV84 commented 8 years ago

I have a rgb-d camera connected which is not supported by openni, I think. I run rtabmap RGB mode but the return is: CameraRGB.cpp:787::init() Parameter "rectifyImages" is set, but no camera model is loaded or valid The camera is /dev/video0 The Depth is /dev/video1 How to fix that?

matlabbe commented 8 years ago

Hi,

This particular error is that rectification option is enabled, but no calibration file is provided. What is your camera? Using both streams from /dev/video0 and /dev/video1 at the same time will not work with RTAB-Map standalone app. You may have to use ROS version of RTAB-Map instead (rtabmap_ros), and create/find a node that can stream your RGB-D images in a format similar to freenect_launch or openni_launch. Some examples with other cameras on this tutorial.

cheers

AndreV84 commented 8 years ago

The camera is https://www.leopardimaging.com/uploads/LI-ESP870-STEREO-M031_datasheet.pdf . It has /dev/video0 YUV and /dev/video1 depth . Howto create the calibration file?Can the file be created using rtabmap? What nodes?

cheers

willdzeng commented 8 years ago

You may need to write a simple wrapper for your camera in ROS that publishing RGB and Depth images using OpencCv using cv::VideoCapture, for exmaple: https://github.com/transcendrobotics/zed_cpu_ros/blob/master/src/zed_cpu_ros.cpp#L35

matlabbe commented 8 years ago

Related post on ROS answers: http://answers.ros.org/question/237939/leopard-imaging-li-esp870-stereo-m031-with-ros/

If the camera is calibrated (I assume yes if it outputs depth images), the calibration parameters should be somewhere. As referred in the link above, it seems there is an SDK to get images, so maybe the calibration parameters can be obtained with it.

I think the easier is to create a ROS driver for this camera. As @willdzeng said, cv::VideoCapture could be used to get the streams. The color images should be converted to BGR or grayscale, and depth image should be converted to unsigned short 16 bits (millimeters) or float 32 bits (meters). See also REP 118.

A compatible calibration file can be created manually in Preferences->Source->Create Calibration. If you are using ROS, you would publish a sensor_msgs/CameraInfo message directly along 2 sensor_msgs/Image messages.

If you don't know ROS, a driver could be created in RTAB-Map library directly. See CameraRGB, CameraRGBD and CameraStereo for some examples.

cheers