Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Breaking detection iterations, because of missing depth #125

Open
MasterRoboticist opened this issue Dec 1, 2020 · 3 comments
Open

Breaking detection iterations, because of missing depth #125

MasterRoboticist opened this issue Dec 1, 2020 · 3 comments

Comments

@MasterRoboticist
Copy link

MasterRoboticist commented Dec 1, 2020

I'm trying to use RGBD SLAM with a stereo camera, but I'm running into some issues. My stereo camera does not provide a depth image, only a point cloud. Is it possible to use RGBD SLAM without a depth image?
I've set wide_topic to my image topic and wide_cloud_topic to my point cloud topic. The gui will start up and then crash. The relevant terminal output is copied below:

`[ INFO] [1606856164.016129785, 8.646000000]: Listening to /multisense/camera/left/image_mono and /multisense/image_points2
[ INFO] [1606856165.718512355, 8.754000000]: No devices connected.... waiting for devices to be connected
[ INFO] [1606856166.893925217, 8.808000000]: Received data from stereo cam
[ WARN] [1606856166.894056994, 8.808000000]: First RGBD-Data Received
[ INFO] [1606856166.930965203, 8.810500000]: Construction of Node with ORB Features
Breaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depthBreaking detection iterations, because of missing depth[ INFO] [1606856166.998135819, 8.812500000]: Feature 2d size: 0, 3D: 0
[ INFO] [1606856166.998223871, 8.812500000]: Feature 2d size: 0, 3D: 0
[ INFO] [1606856166.998527628, 8.812500000]: Feature Count of Node: 0
[ WARN] [1606856167.105916519, 8.817500000]: "openni_rgb_optical_frame" passed to lookupTransform argument target_frame does not exist.
[ WARN] [1606856167.105981903, 8.817500000]: Using Standard kinect /openni_camera -> /openni_rgb_optical_frame as transformation (This message is throttled to 1 per 5 seconds)
OpenCV Error: Assertion failed (i1 >= 0 && j < ndsts && dst[j].depth() == depth) in mixChannels, file /tmp/binarydeb/ros-kinetic-opencv3-3.3.1/modules/core/src/convert.cpp, line 614
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/binarydeb/ros-kinetic-opencv3-3.3.1/modules/core/src/convert.cpp:614: error: (-215) i1 >= 0 && j < ndsts && dst[j].depth() == depth in function mixChannels

REQUIRED process [rgbdslam-25] has died!
process has died [pid 4765, exit code -6, cmd /home/emily/catkin_ws/devel/lib/rgbdslam/rgbdslam __name:=rgbdslam __log:=/home/emily/.ros/log/4e9bc55e-3417-11eb-afef-5c3a45e01c7d/rgbdslam-25.log].
log file: /home/emily/.ros/log/4e9bc55e-3417-11eb-afef-5c3a45e01c7d/rgbdslam-25*.log
Initiating shutdown!
`

@felixendres
Copy link
Owner

felixendres commented Dec 3, 2020

For stereo the data an image synced with a pointcloud is received here
and a depth image is computed from the cloud here. This doesn't seem to work, as this function says there are no depth values in your cloud.

Not sure why it crashes then. I don't have time to investigate. As a quick fix, I recommend you insert the check for depth-less cloud/depth-image somewhere here and just abort processing of that image+cloud in that case (just return from stereoCallback()).

@MasterRoboticist
Copy link
Author

Thanks! Turns out the problem isn't related to the depth image. I implemented your fix and it skips depth-less depth images, but when the depth image isn't empty, it throws the same warning and opencv error and then crashes (re-copied below for clarity). We'll keep looking into it ourselves, but if you have any ideas we would be grateful.

`[ WARN] [1607436291.753501698, 24.719500000]: "openni_rgb_optical_frame" passed to lookupTransform argument target_frame does not exist.
[ WARN] [1607436291.753555448, 24.719500000]: Using Standard kinect /openni_camera -> /openni_rgb_optical_frame as transformation (This message is throttled to 1 per 5 seconds)
OpenCV Error: Assertion failed (i1 >= 0 && j < ndsts && dst[j].depth() == depth) in mixChannels, file /tmp/binarydeb/ros-kinetic-opencv3-3.3.1/modules/core/src/convert.cpp, line 614
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/binarydeb/ros-kinetic-opencv3-3.3.1/modules/core/src/convert.cpp:614: error: (-215) i1 >= 0 && j < ndsts && dst[j].depth() == depth in function mixChannels

REQUIRED process [rgbdslam-25] has died!
`

@felixendres
Copy link
Owner

Then, the best first step is finding out where the error occurs. Try obtaining a stack trace. Either run rgbdslam in gdb (see here for to do it with a launch file), or enable core dumps (ulimit -c unlimited) and inspect it with gdb (gdb /path/to/rgbdslam ./core). In gdb "bt" will give you the backtrace. You may need to switch to the respective thread first.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants