ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
RGBDSLAM requires /camera/depth/image (which contains float values in meter), not /camera/depth/image_raw (which provides 16bit integer values in mm). If you don't want to re-record the data and know C++, you can add a conversion in src/openni_listener.cpp in the method
void OpenNIListener::noCloudCallback (const sensor_msgs::ImageConstPtr& visual_img_msg,...)
There are two lines:
cv::Mat depth_float_img = cv_bridge::toCvCopy(depth_img_msg)->image;
Add changes s.t. the image is converted to float and meter there.
2 | No.2 Revision |
RGBDSLAM requires /camera/depth/image (which contains float values in meter), not /camera/depth/image_raw (which provides 16bit integer values in mm). If you don't want to re-record the data and know C++, you can add a conversion in src/openni_listener.cpp in the method
void OpenNIListener::noCloudCallback (const sensor_msgs::ImageConstPtr& visual_img_msg,...)
There are two lines:
cv::Mat depth_float_img = cv_bridge::toCvCopy(depth_img_msg)->image;
Add changes s.t. the image is converted to float and meter there.
Please try:
cv::Mat depth_float_img2;
depth_float_img.convertTo(depth_float_img2,CV_32FC1);
depth_float_img = depth_float_img2 * 0.001
This should avoid all problems with casting and inplace. Hope that helps with the crash. Otherwise try setting the debug-flag in the launchfile (line 9) and see where (and hopefully why) it crashes.