Skip to content

Pose Graph rewritten without Ceres #2892

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

Merged
merged 51 commits into from
Apr 1, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
51 commits
Select commit Hold shift + click to select a range
9ff635e
Works well on g2o dataset, cumulative:
savuor Mar 8, 2021
69d05df
g2o dataset reading added to PoseGraph
savuor Mar 9, 2021
f89247d
sparse solver fixes from DynaFu draft
savuor Mar 11, 2021
92834f8
Eigen cost function and parametrization removed + g2o reading fixed
savuor Mar 11, 2021
fdd92ce
refactored: pose error, pose graph edge, pose graph node
savuor Mar 11, 2021
f71f862
sparse solve: templated
savuor Mar 11, 2021
01b1608
MyOptimize(): 1st version
savuor Mar 11, 2021
ff782d1
several fixes and TODOs for future
savuor Mar 12, 2021
9b2fa9d
sparse block matrix: val functions, template type
savuor Mar 19, 2021
ccb4262
works at Ceres quality (cleanup needed)
savuor Mar 19, 2021
7a2126c
MyOptimize() is set to default optimizer
savuor Mar 21, 2021
638b8d7
Ceres thrown away, PoseGraph class and header/source code reorganized
savuor Mar 21, 2021
91b0b27
pose, node, edge -> nested for PoseGraph
savuor Mar 21, 2021
264ccbf
warnings fixed
savuor Mar 22, 2021
c3bb3a6
jacobiScaling disabled for better performance + minors
savuor Mar 22, 2021
512b40f
trailing whitespace fixed
savuor Mar 22, 2021
155e3eb
more warnings fixed
savuor Mar 22, 2021
e90100f
message added: Eigen is required for build + minors
savuor Mar 22, 2021
7c1a205
trying to fix warning
savuor Mar 22, 2021
87c959f
try to fix "unreachable code" warning
savuor Mar 23, 2021
2d5bd7e
trying to fix unreachable code, pt.3
savuor Mar 23, 2021
8d64f2a
trying to fix unreachable code, pt. 5
savuor Mar 23, 2021
a37c1ba
trying to fix unreachable code, pt. the worst + minors
savuor Mar 23, 2021
54264ba
try to fix unreachable code, pt. the ugliest
savuor Mar 24, 2021
25d67f8
trying to fix unreachable code, pt. the grumpiest
savuor Mar 24, 2021
170f1f3
cout -> CV_LOG_INFO
savuor Mar 24, 2021
ca6eef2
quat matrix functions moved outside cv and kinfu namespaces
savuor Mar 24, 2021
a718ade
unused function fix
savuor Mar 24, 2021
ae792cf
pose graph made public (but in detail namespace) + test for pose graph
savuor Mar 28, 2021
afd11f3
minor: prints
savuor Mar 28, 2021
6f4da67
Pose Graph interface settled
savuor Mar 28, 2021
c6f730f
Pose graph interface and its use updated
savuor Mar 29, 2021
9969c10
cos -> std::cos
savuor Mar 29, 2021
38a9b29
cout -> CV_LOG_INFO
savuor Mar 29, 2021
0be999d
pose graph interface updated: implementation
savuor Mar 29, 2021
de7a39c
Pose Graph Node and Edge: extra fields dropped
savuor Mar 29, 2021
c8d3c6e
more minor refactor-like fixes
savuor Mar 29, 2021
d31536f
return and finish condition fixed
savuor Mar 29, 2021
a3d6741
more updates to test
savuor Mar 29, 2021
f53b44c
test disabled for Debug builds because 400 sec is too much
savuor Mar 29, 2021
5c6c126
whitespace
savuor Mar 29, 2021
f9adf77
Disable pose graph test if there's no Eigen
savuor Mar 30, 2021
1e67e3c
more unused vars
savuor Mar 30, 2021
5527997
fixing unused function warning
savuor Mar 30, 2021
2756e62
less includes
savuor Mar 30, 2021
5d13e84
"verbose" removed
savuor Mar 31, 2021
8fcf78b
write obj to file only when debug level is raised
savuor Mar 31, 2021
a99db27
License + include guard
savuor Mar 31, 2021
c30d23c
skip test using tags and SkipTestException
savuor Mar 31, 2021
ebed66b
suppress "unused function" warning
savuor Mar 31, 2021
e1e5ff7
minor
savuor Apr 1, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 2 additions & 10 deletions modules/rgbd/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,15 +1,7 @@
set(the_description "RGBD algorithms")

find_package(Ceres QUIET)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does it make sense to keep both implementations (to compare results) for some timeframe (e.g., until we have robust tests)?

ocv_define_module(rgbd opencv_core opencv_calib3d opencv_imgproc OPTIONAL opencv_viz WRAP python)

if(Ceres_FOUND)
ocv_target_compile_definitions(${the_module} PUBLIC CERES_FOUND)
ocv_target_link_libraries(${the_module} ${CERES_LIBRARIES})
if(Ceres_VERSION VERSION_LESS 2.0.0)
ocv_include_directories("${CERES_INCLUDE_DIRS}")
endif()
add_definitions(/DGLOG_NO_ABBREVIATED_SEVERITIES) # avoid ERROR macro conflict in glog (ceres dependency)
else()
message(STATUS "rgbd: CERES support is disabled. Ceres Solver is Required for Posegraph optimization")
if(NOT HAVE_EIGEN)
message(STATUS "rgbd: Eigen support is disabled. Eigen is Required for Posegraph optimization")
endif()
1 change: 1 addition & 0 deletions modules/rgbd/include/opencv2/rgbd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "opencv2/rgbd/kinfu.hpp"
#include "opencv2/rgbd/dynafu.hpp"
#include "opencv2/rgbd/large_kinfu.hpp"
#include "opencv2/rgbd/detail/pose_graph.hpp"


/** @defgroup rgbd RGB-Depth Processing
Expand Down
62 changes: 62 additions & 0 deletions modules/rgbd/include/opencv2/rgbd/detail/pose_graph.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html

#ifndef OPENCV_RGBD_POSE_GRAPH_HPP
#define OPENCV_RGBD_POSE_GRAPH_HPP

#include "opencv2/core/affine.hpp"
#include "opencv2/core/quaternion.hpp"

namespace cv
{
namespace kinfu
{
namespace detail
{

// ATTENTION! This class is used internally in Large KinFu.
// It has been pushed to publicly available headers for tests only.
// Source compatibility of this API is not guaranteed in the future.

// This class provides tools to solve so-called pose graph problem often arisen in SLAM problems
// The pose graph format, cost function and optimization techniques
// repeat the ones used in Ceres 3D Pose Graph Optimization:
// http://ceres-solver.org/nnls_tutorial.html#other-examples, pose_graph_3d.cc bullet
class CV_EXPORTS_W PoseGraph
{
public:
static Ptr<PoseGraph> create();
virtual ~PoseGraph();

// Node may have any id >= 0
virtual void addNode(size_t _nodeId, const Affine3d& _pose, bool fixed) = 0;
virtual bool isNodeExist(size_t nodeId) const = 0;
virtual bool setNodeFixed(size_t nodeId, bool fixed) = 0;
virtual bool isNodeFixed(size_t nodeId) const = 0;
virtual Affine3d getNodePose(size_t nodeId) const = 0;
virtual std::vector<size_t> getNodesIds() const = 0;
virtual size_t getNumNodes() const = 0;

// Edges have consequent indices starting from 0
virtual void addEdge(size_t _sourceNodeId, size_t _targetNodeId, const Affine3f& _transformation,
const Matx66f& _information = Matx66f::eye()) = 0;
virtual size_t getEdgeStart(size_t i) const = 0;
virtual size_t getEdgeEnd(size_t i) const = 0;
virtual size_t getNumEdges() const = 0;

// checks if graph is connected and each edge connects exactly 2 nodes
virtual bool isValid() const = 0;

// Termination criteria are max number of iterations and min relative energy change to current energy
// Returns number of iterations elapsed or -1 if max number of iterations was reached or failed to optimize
virtual int optimize(const cv::TermCriteria& tc = cv::TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 100, 1e-6)) = 0;

// calculate cost function based on current nodes parameters
virtual double calcEnergy() const = 0;
};

} // namespace detail
} // namespace kinfu
} // namespace cv
#endif /* ifndef OPENCV_RGBD_POSE_GRAPH_HPP */
4 changes: 2 additions & 2 deletions modules/rgbd/src/fast_icp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -504,7 +504,7 @@ void ICPImpl::getAb<Mat>(const Mat& oldPts, const Mat& oldNrm, const Mat& newPts
const Normals np(newPts), nn(newNrm);
GetAbInvoker invoker(sumAB, mutex, op, on, np, nn, pose,
intrinsics.scale(level).makeProjector(),
distanceThreshold*distanceThreshold, cos(angleThreshold));
distanceThreshold*distanceThreshold, std::cos(angleThreshold));
Range range(0, newPts.rows);
const int nstripes = -1;
parallel_for_(range, invoker, nstripes);
Expand Down Expand Up @@ -590,7 +590,7 @@ void ICPImpl::getAb<UMat>(const UMat& oldPts, const UMat& oldNrm, const UMat& ne
sizeof(pose.matrix.val)),
fxy.val, cxy.val,
distanceThreshold*distanceThreshold,
cos(angleThreshold),
std::cos(angleThreshold),
ocl::KernelArg::Local(lsz),
ocl::KernelArg::WriteOnlyNoSize(groupedSumGpu)
);
Expand Down
25 changes: 16 additions & 9 deletions modules/rgbd/src/large_kinfu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,7 @@ bool LargeKinfuImpl<UMat>::update(InputArray _depth)
}
}


template<typename MatType>
bool LargeKinfuImpl<MatType>::updateT(const MatType& _depth)
{
Expand All @@ -224,14 +225,14 @@ bool LargeKinfuImpl<MatType>::updateT(const MatType& _depth)
params.bilateral_sigma_depth, params.bilateral_sigma_spatial, params.bilateral_kernel_size,
params.truncateThreshold);

std::cout << "Current frameID: " << frameCounter << "\n";
CV_LOG_INFO(NULL, "Current frameID: " << frameCounter);
for (const auto& it : submapMgr->activeSubmaps)
{
int currTrackingId = it.first;
auto submapData = it.second;
Ptr<Submap<MatType>> currTrackingSubmap = submapMgr->getSubmap(currTrackingId);
Affine3f affine;
std::cout << "Current tracking ID: " << currTrackingId << std::endl;
CV_LOG_INFO(NULL, "Current tracking ID: " << currTrackingId);

if(frameCounter == 0) //! Only one current tracking map
{
Expand All @@ -248,7 +249,7 @@ bool LargeKinfuImpl<MatType>::updateT(const MatType& _depth)
currTrackingSubmap->composeCameraPose(affine);
else
{
std::cout << "Tracking failed" << std::endl;
CV_LOG_INFO(NULL, "Tracking failed");
continue;
}

Expand All @@ -267,8 +268,8 @@ bool LargeKinfuImpl<MatType>::updateT(const MatType& _depth)

currTrackingSubmap->updatePyrPointsNormals(params.pyramidLevels);

std::cout << "Submap: " << currTrackingId << " Total allocated blocks: " << currTrackingSubmap->getTotalAllocatedBlocks() << "\n";
std::cout << "Submap: " << currTrackingId << " Visible blocks: " << currTrackingSubmap->getVisibleBlocks(frameCounter) << "\n";
CV_LOG_INFO(NULL, "Submap: " << currTrackingId << " Total allocated blocks: " << currTrackingSubmap->getTotalAllocatedBlocks());
CV_LOG_INFO(NULL, "Submap: " << currTrackingId << " Visible blocks: " << currTrackingSubmap->getVisibleBlocks(frameCounter));

}
//4. Update map
Expand All @@ -277,13 +278,19 @@ bool LargeKinfuImpl<MatType>::updateT(const MatType& _depth)
if(isMapUpdated)
{
// TODO: Convert constraints to posegraph
PoseGraph poseGraph = submapMgr->MapToPoseGraph();
std::cout << "Created posegraph\n";
Optimizer::optimize(poseGraph);
Ptr<kinfu::detail::PoseGraph> poseGraph = submapMgr->MapToPoseGraph();
CV_LOG_INFO(NULL, "Created posegraph");
int iters = poseGraph->optimize();
if (iters < 0)
{
CV_LOG_INFO(NULL, "Failed to perform pose graph optimization");
return false;
}

submapMgr->PoseGraphToMap(poseGraph);

}
std::cout << "Number of submaps: " << submapMgr->submapList.size() << "\n";
CV_LOG_INFO(NULL, "Number of submaps: " << submapMgr->submapList.size());

frameCounter++;
return true;
Expand Down
2 changes: 1 addition & 1 deletion modules/rgbd/src/nonrigid_icp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ bool ICPImpl::estimateWarpNodes(WarpField& currentWarp, const Affine3f &pose,

Vec3f diff = oldPoints.at<Vec3f>(y, x) - Vec3f(newP);
if(diff.dot(diff) > 0.0004f) continue;
if(abs(newN.dot(oldNormals.at<Point3f>(y, x))) < cos((float)CV_PI / 2)) continue;
if(abs(newN.dot(oldNormals.at<Point3f>(y, x))) < std::cos((float)CV_PI / 2)) continue;

float rd = newN.dot(diff);

Expand Down
Loading