alejocb / dpptam

DPPTAM: Dense Piecewise Planar Tracking and Mapping from a Monocular Sequence
GNU General Public License v3.0
219 stars 82 forks source link

OpenCV error: Assertion failed (at DenseMapping.cpp Line 605) #33

Open TomoshibiAkira opened 7 years ago

TomoshibiAkira commented 7 years ago

Hi @alejocb , thank you for your hard work on the code!

I encountered the same problem as @sunghoon031 did in #9 . My OpenCV version is 2.4.8 which is the latest version in Ubuntu 14.04 LTS, reinstalling ROS and OpenCV didn't resolve it. Then I decided to debug DPPTAM, found out that the push_back() at DenseMapping.cpp Line 605 is the cause.

cv::Mat distances_btw_3dpoints(0,1,CV_32FC1);
for (int ii = 0; ii < 20; ii++)
{
    int random_row1 = (rand() % points_sup_total.rows);
    int random_row2 = (rand() % points_sup_total.rows);
    // Line 605
    distances_btw_3dpoints.push_back(cv::norm(points_sup_total.colRange(0,3).row(random_row1)-points_sup_total.colRange(0,3).row(random_row2),cv::NORM_L1) / 3);
}

cv::norm() returns a 8-byte double type float, but the element type of distances_btw_3dpoints is CV_32FC1, which is a 4-byte float type float, that's the reason why the assertion inside push_back() is failed. The problem is solved after adding a type casting.

What really confuses me is this problem seems kinda random. For testing I created a virtual machine running the same operation system (Ubuntu 14.04 LTS), then set the entire ROS environment from clean install, build DPPTAM, and it runs perfectly, but it shouldn't because the type of element is different.

gabrielmirandat commented 6 years ago

Where exactly have you cast it? Could you show how you did?