symao / PnPL

Perspective n Point and Line for camera pose estimation.
135 stars 47 forks source link

Vector 4D not defined in the scope #1

Open zouyajing opened 6 years ago

zouyajing commented 6 years ago

I got several error message in pnpl.cpp. It seems that after the line typedef Eigen::Matrix<double,6,1,Eigen::ColMajor> Vector6D; Vector4D 3D 2D shoule also be defined.

After I fixed this, I got problems with the API of G2O. So I changed to link an early version G2O, and it is OK now.

/home/rick/SLAMProjects/PnPL/src/pnpl.cpp: In function ‘void PnPL(const std::vector<cv::Point3 >&, const std::vector<cv::Point >&, const std::vector<cv::Vec<float, 6> >&, const std::vector<cv::Vec<float, 4> >&, const cv::Mat&, cv::Mat&, cv::Mat&)’: /home/rick/SLAMProjects/PnPL/src/pnpl.cpp:143:78: error: no matching function for call to ‘g2o::BlockSolver<g2o::BlockSolverTraits<6, 3> >::BlockSolver(g2o::BlockSolver<g2o::BlockSolverTraits<6, 3> >::LinearSolverType&)’ g2o::BlockSolver_6_3 solver_ptr = new g2o::BlockSolver_6_3(linearSolver); ^ In file included from /usr/local/include/g2o/core/block_solver.h:199:0, from /home/rick/SLAMProjects/PnPL/src/pnpl.cpp:4: /usr/local/include/g2o/core/block_solver.hpp:40:1: note: candidate: g2o::BlockSolver::BlockSolver(std::unique_ptr) [with Traits = g2o::BlockSolverTraits<6, 3>; typename Traits::LinearSolverType = g2o::LinearSolver<Eigen::Matrix<double, 6, 6, 0> >] BlockSolver::BlockSolver(std::unique_ptr linearSolver) ^ /usr/local/include/g2o/core/block_solver.hpp:40:1: note: no known conversion for argument 1 from ‘g2o::BlockSolver<g2o::BlockSolverTraits<6, 3> >::LinearSolverType {aka g2o::LinearSolver<Eigen::Matrix<double, 6, 6, 0> >}’ to ‘std::unique_ptr<g2o::LinearSolver<Eigen::Matrix<double, 6, 6, 0> >, std::default_delete<g2o::LinearSolver<Eigen::Matrix<double, 6, 6, 0> > > >’ /home/rick/SLAMProjects/PnPL/src/pnpl.cpp:144:101: error: no matching function for call to ‘g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(g2o::BlockSolver_6_3&)’ g2o::OptimizationAlgorithmLevenberg solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); ^ In file included from /home/rick/SLAMProjects/PnPL/src/pnpl.cpp:7:0: /usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note: candidate: g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(std::unique_ptr) explicit OptimizationAlgorithmLevenberg(std::unique_ptr solver); ^ /usr/local/include/g2o/core/optimization_algorithm_levenberg.h:47:16: note: no known conversion for argument 1 from ‘g2o::BlockSolver_6_3 {aka g2o::BlockSolver<g2o::BlockSolverTraits<6, 3> >}’ to ‘std::unique_ptr’ CMakeFiles/demo_pnpl.dir/build.make:86: recipe for target 'CMakeFiles/demo_pnpl.dir/src/pnpl.cpp.o' failed make[2]: [CMakeFiles/demo_pnpl.dir/src/pnpl.cpp.o] Error 1 CMakeFiles/Makefile2:104: recipe for target 'CMakeFiles/demo_pnpl.dir/all' failed make[1]: [CMakeFiles/demo_pnpl.dir/all] Error 2 Makefile:83: recipe for target 'all' failed make: *** [all] Error 2

matt-deboer commented 6 years ago

I was able to resolve this by comparing with the new g2o api example here: https://github.com/RainerKuemmerle/g2o/blob/master/g2o/examples/ba/ba_demo.cpp (along with adding missing typedefs for the Vector*D types)

zhangjun-xyz commented 5 years ago

@matt-deboer I still cannot figure out how did you solve this problem. Can you explain more in details, please?

Zedzou commented 4 years ago

@zhangjun-xyz Did you sloved it, I meet it too and do not know what it is meaning. thank you

zhangjun-xyz commented 4 years ago

@Zedzou Sorry I don't focus on this project for a long time. But as a reminder I guess it's caused by wrong g2o version. You can check it. Hope this can help you. :)

allenthreee commented 2 years ago
// init g2o, the init func shuold match the g2o version
// I solved it by substituting old version init using new version
// my g2o is 20200410 
// **********************old version(20170730_git) g2o solver init*******************************
g2o::BlockSolver_6_3::LinearSolverType * linearSolver;
linearSolver= new g2o::LinearSolverCSparse<g2o::BlockSolver_6_3::PoseMatrixType>();
g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver);
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);
// *******************************************************************************************
// **********************new version(20200410) g2o solver init*******************************
// ******************if you use new g2o, the construction function should match*************
typedef g2o::LinearSolverCSparse<g2o::BlockSolver_6_3::PoseMatrixType> LinearType;
auto linearSolver= std::unique_ptr<LinearType>(new LinearType); 
auto solver_ptr = std::unique_ptr<g2o::BlockSolver_6_3>(new g2o::BlockSolver_6_3(std::move(linearSolver))); 
auto solver = new g2o::OptimizationAlgorithmLevenberg( std::move(solver_ptr) );
// **********************************finally we can init the optimizer***************************
g2o::SparseOptimizer optimizer;
// optimizer.setVerbose(true);
optimizer.setAlgorithm(solver);
// *******************************************************************************************