Classic BA: How good is good enough? (Initial camera positions)

91 views
Skip to first unread message

Igor

unread,
Aug 26, 2024, 3:54:25 PM8/26/24
to Ceres Solver
Hello and thanks for adding me. I'm in the process of creating a simple SFM program and i have some trouble with the Bundle Adjustment part of it. 
I'm already using ceres for ICP in my program with much success so i think i have the basics of the library intact but i can't get through this problem. My suspects are either poor initial camera positions or something called "degenerate scene" which i found about reading through this forum.
 I would like to ask how good do the initial camera positions have to be? I have prepared some images to show the initial camera positions on one of my reconstructions and what my Bundle Adjustment does with them after 15 iterations. I know its hard to judge anything based on images alone but I'll give it a try. I have checked the positions from my program against Meshroom and they are pretty close.
The cost function I'm using for those reconstructions is SnavelyReprojectionError taken from ceres tutorial. I have also tried SimpleReprojectionError found in sample code on ceres github repo.
 I have taken much care to ensure that all  variables needed to construct ceres problem "live" through the whole optimization process (blind pointers).
 I have checked all the values (camera positions, 3d points, 2d points etc) from within the cost function and they seem ok - no NaN or Inf in there. 
I have also tried different loss functions.
No matter what i do BA always produces what i call "supernovae point clouds".

I'm fighting this problem for over a month and at this point I'm out of ideas. I have studied other programs where ceres BA is used to check for bugs. 
 I have tried it on over 30 different datasets found across the web - i have a lot of point cloud pair where ICP works fine but everything goes south at the BA step - I can upload them to Google Drive if anyone wants to see them. 

My main question is how good the initial camera positions have to be for the BA to work?

Now the code part - as i mentioned above I'm using SnavelyReprojectionError or SimpleReprojectionError and I'm adding residual blocks just like in the ceres tutorial. I'm not sure which part of the code to show and I don't want to make a huge mess so i will add the BA function in the attachments. There is also a full report from 150 iterations where one can notice the gradient rising at first - which i think indicates some problems.

I would be very grateful for any pointers and ideas. If any more info is needed please tell me and i will provide it.

Thank you in advance!


150_iter.txt
fountain.png
cat_BA.png
runSnavely.txt
cat.png
fountain_BA.png

William Rucklidge

unread,
Aug 26, 2024, 5:27:45 PM8/26/24
to ceres-...@googlegroups.com
Just a few general comments; I haven't got any great insight but these are easy places to start looking:

The first few iterations show an immense jump in cost - this is a sign that there's something in the structure of your problem that's not very stable.
What happens if you start with everything perfect? Perfect camera positions, perfect 3D point locations? If it doesn't converge, then that gives you a direction to follow ("why are my residuals and gradients not zero?").
How do you initialise the 3D point locations? It's often good to make them reasonable - for example, the point that is closest to the two camera rays.
What are the magnitude of the coordinates (of the points and the cameras)? If you can, scale them so that they're not too large; it helps when all the variables Ceres is optimising (including the camera rotations and intrinsics, which are bounded) are of about the same magnitude.


--
You received this message because you are subscribed to the Google Groups "Ceres Solver" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/5a1a0664-7c35-4588-b002-59fa7b4f88f6n%40googlegroups.com.

Sameer Agarwal

unread,
Aug 27, 2024, 12:18:59 PM8/27/24
to ceres-...@googlegroups.com
Igor,
Looking at your code it appears to me that you are trying to merge some pairwise reconstructions. So the cameras are not shared between the pairs of reconstructions. But I imagine the reason you are doing bundle adjustment is because 3d points are shared between the pairwise reconstructions. If that is the case, then the way you are constructing the problem is wrong. The inner loop of your problem construction creates a unique parameter block for each 3d point from each pairwise reconstruction. 

This means that there is nothing tying the various pairwise reconstructions together, you are essentially optimizing n pairwise reconstructions independently, and since pairwise reconstructions are not terribly well conditioned you are getting the weird point clouds.
Sameer


Igor

unread,
Sep 2, 2024, 4:47:01 PM9/2/24
to Ceres Solver
wjr, Sameer, 

thanks for your replies and excuse my late reply, I had to digest what you both said.

First the missing context about my program. As Sameer noticed my program runs on image pair structures. It relies on the images being in the correct order (ordered datasets). The pairs are simply constructed like that: 
Pair1 = image1, image2. 
Pair2 = image2, image3. 
Pair3 = image3, image4 and so on.
There is always overlap between pairs. This is the reason why there are 2 addResidualBlock functions per pair.

@wjr - Yes the gradient jumping all over the place definately isn't good. I will adapt your idea of using a "perfect" (or close to perfect) dataset of points and cameras and will use it for testing but i have to find such dataset first. 
For the normalization part - I'm using openCV for the first part of the program (feature matching, camera poses, triangulation) which gives Point coordinates usualy within <-10,10> in all axes (after filtering and rejecting "wild" 3d points). I will try to scale them down some more.

@Sameer - I'm not sure if I understood correctly but what you wrote looks like there should be corespondences between partial point clouds included in the Problem. This indicates that I have missed an essential part of how bundle adjustment works. My program uses ICP to align partial point clouds so it has a 3d correspondence search algorithm in it. It's been 6 days since your reply so i had some time to experiment and this is what i came up with:

Restructuring all partial point clouds into a single vector where 2 types of points are present: those that have correspondece with "next" point cloud and those that dont.
Point with correspondence have 3 cameras they are visible in - 2 cameras from N'th pair and 1 camera from N+1'th pair - those are (hopefully) the "ties" you mentioned.
Points without correspondence have 2 cameras, just like before.

It's all packed in a vector of structures:

struct PointBA {
    double p3d[3];
    std::vector<std::array<double, 9>> cams;
    std::vector<std::array<double, 2>> p2d;
};

Now if a 3d Point has a correspondence in the "next" partial point cloud its 3d coordinates are slightly different in those partial point clouds. ICP aligns partial point clouds but it's not perfect because there is noise and distortions in those clouds. For now I'm just calculating average 3d coordinates.

Finally I'm passing all this into residual blocks like this:

 for (int p = 0; p < pointsBA.size(); p++) { 
     for (int c = 0; c < pointsBA[p].cams.size(); c++) { 
         ceres::CostFunction* cost_function1 = SnavelyReprojectionError::Create(pointsBA[p].p2d[c][0], pointsBA[p].p2d[c][1]);
         problem.AddResidualBlock(cost_function1, huber, pointsBA[p].cams[c].data(), pointsBA[p].p3d);
     }
 }

Is this a more reasonable approach?

I have already done some test with the above configuration. It's a little better now but all previous issues remain. The point clouds don't "explode" anymore, they are just distorted. I have run some test with small datasets (~7-10 images) and in some cases the optimisation didn't converge after 1000 steps. There is alot of unsuccessful steps.

Any more help highly appreciated.

Thank you

Sameer Agarwal

unread,
Sep 4, 2024, 9:36:01 AM9/4/24
to ceres-...@googlegroups.com
Igor,
I am pointing out a much simpler problem with your code.

Let us assume that your dataset has two pairs.

Pair1 = image1, image2. 
Pair2 = image2, image3. 

then you only have three actual cameras. Now let us look at your code for constructing the optimization problem


    std::vector<std::array<double, 9>> cams1, cams2;    
    for (int p = 0; p < data.pairVec.size(); p++) {
        std::array<double, 9> cam1 = { data.pairVec[p].rr1[0], data.pairVec[p].rr1[1], data.pairVec[p].rr1[2],     // the same positions are used to produce "camera frustums" in the point cluds
                           data.pairVec[p].t1[0], data.pairVec[p].t1[1], data.pairVec[p].t1[2],
                           data.pairVec[p].arrK[0], 0, 0 };

        cams1.push_back(cam1);

        std::array<double, 9> cam2 = { data.pairVec[p].rr2[0], data.pairVec[p].rr2[1], data.pairVec[p].rr2[2],
                           data.pairVec[p].t2[0], data.pairVec[p].t2[1], data.pairVec[p].t2[2],
                           data.pairVec[p].arrK[0], 0, 0 };

        cams2.push_back(cam1);

    } 

In the above loop you have created four cameras, in effect two copies of the camera for image 2.

 
    ceres::LossFunction* huber = new ceres::HuberLoss(16.0);
    //ceres::LossFunction* tukey = new ceres::TukeyLoss(4.0);

    for (int p = 0; p < data.pairVec.size(); ++p) { // outer loop for each image pair

        for (int i = 0; i < data.pairVec[p].pointsSFM.size(); ++i) {  // inner loop for each observation in pair. There are always 2 cameras for each observation in each pair - this "pair structure" is true across the whole program        

            ceres::CostFunction* cost_function1 = SnavelyReprojectionError::Create(data.pairVec[p].pointsSFM[i].pImg1X, data.pairVec[p].pointsSFM[i].pImg1Y);
            problem.AddResidualBlock(cost_function1, huber, cams1[p].data(), data.pairVec[p].pointsSFM[i].p3d);

            ceres::CostFunction* cost_function2 = SnavelyReprojectionError::Create(data.pairVec[p].pointsSFM[i].pImg2X, data.pairVec[p].pointsSFM[i].pImg2Y);
            problem.AddResidualBlock(cost_function2, huber, cams2[p].data(), data.pairVec[p].pointsSFM[i].p3d);

        }

    }

In the above loop you are creating residual blocks per camera pair. Across camera pairs unless you are sharing 3d points, and I do not think you are, there is no relationship between your 2 camera pairs. So are setting up two entirely independent optimization problems inside one ceres::Problem and solving them.

What you want to do instead is create 3 arrays holding your cameras and index into them correctly.

As for points, what you suggest makes sense, where you merge all the points into one point cloud and at least some of the points have shared visibility. 

@Sameer - I'm not sure if I understood correctly but what you wrote looks like there should be corespondences between partial point clouds included in the Problem. This indicates that I have missed an essential part of how bundle adjustment works. My program uses ICP to align partial point clouds so it has a 3d correspondence search algorithm in it. It's been 6 days since your reply so i had some time to experiment and this is what i came up with:

Restructuring all partial point clouds into a single vector where 2 types of points are present: those that have correspondece with "next" point cloud and those that dont.
Point with correspondence have 3 cameras they are visible in - 2 cameras from N'th pair and 1 camera from N+1'th pair - those are (hopefully) the "ties" you mentioned.
Points without correspondence have 2 cameras, just like before.

It's all packed in a vector of structures:

struct PointBA {
    double p3d[3];
    std::vector<std::array<double, 9>> cams;
    std::vector<std::array<double, 2>> p2d;
};


This is incorrect.  Why does each point have a copy of its own cameras? The cameras should be shared across all points. What you want is an array of cameras and each point carries an index into that array of cameras. Something like the following.

std::vector<std:array<double, 9> cams;
struct PointBA {
    double p3d[3];
    std::vector<int> cams;

    std::vector<std::array<double, 2>> p2d;
};

 for (int p = 0; p < pointsBA.size(); p++) { 
     for (int c = 0; c < pointsBA[p].cams.size(); c++) { 
         ceres::CostFunction* cost_function1 = SnavelyReprojectionError::Create(pointsBA[p].p2d[c][0], pointsBA[p].p2d[c][1]);
         problem.AddResidualBlock(cost_function1, huber, cams[pointsBA[p].cams[c]], pointsBA[p].p3d);
     }
 }

Sameer

Reply all
Reply to author
Forward
0 new messages