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

Feature enhancement: PnP algorithm for pose Matrix calculation and other functions improves #23

Merged
merged 35 commits into from
Apr 1, 2024
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
c22785c
creating WebARKitPattern struct see #21
kalwalt Nov 1, 2023
e91098e
using push_back to avoid an Seg fault
kalwalt Nov 1, 2023
5e2d37b
getPoseMatrix function and improved computePose
kalwalt Nov 2, 2023
0647381
trying to find the root of the pose matrix issue
kalwalt Nov 3, 2023
d383ac9
cleaning the code
kalwalt Nov 4, 2023
40017fc
The issue arise the wrong camera matrix data
kalwalt Nov 4, 2023
d13feef
this seems to be correct!
kalwalt Nov 4, 2023
bfcebc9
improved classes and features
kalwalt Nov 4, 2023
684d9c6
new WebARKitGL collection of GL functions
kalwalt Nov 5, 2023
809471e
fix for wrong cv headers
kalwalt Nov 5, 2023
e3997cb
values and params should be double
kalwalt Nov 6, 2023
ad15a7f
make GL mfunctions part of ebarkit namespace
kalwalt Nov 6, 2023
d01a0a1
revert to old syntax pattern
kalwalt Nov 6, 2023
0d74031
new cameraProjectionMatrix with gtest
kalwalt Nov 6, 2023
dce5a2a
getCameraProjectioMatrix with gtest
kalwalt Nov 6, 2023
ce4fe4d
fix for: Test issue: impossible to load a jpeg image with imread (Ope…
kalwalt Nov 9, 2023
fe46f86
add to initTracker colorSpace option to let use other colors channels
kalwalt Nov 10, 2023
f6dfcbc
pinball image is 3 channels add support for this type to initTracker
kalwalt Nov 10, 2023
218eda8
processFrameData now may process also RGB data input
kalwalt Nov 10, 2023
022b559
new convert2Grayscale function to avoid repetitions
kalwalt Nov 11, 2023
47e102f
oveloaded convert2Grayscale function and other fixes
kalwalt Nov 13, 2023
8cc8572
testing matrix and cameraProjmatrix
kalwalt Nov 16, 2023
a68af51
sphere is displayed but don't move
kalwalt Nov 18, 2023
bd21912
_isDetected = false should be outside clear_output()
kalwalt Nov 18, 2023
2dff6c4
initTracker as templatized function
kalwalt Nov 18, 2023
04a5bb2
Fix swapImage and other related code
kalwalt Dec 5, 2023
e3cdf48
small improves
kalwalt Mar 3, 2024
63946b4
fix for MIN_NUM_MATCHES failed test
kalwalt Mar 4, 2024
e754f20
move marker dected message inside processFrame
kalwalt Mar 8, 2024
e9c7fb1
new extractFeatures method
kalwalt Mar 15, 2024
afac6e7
new boolean option enablleBlur
kalwalt Mar 20, 2024
6043029
more modularity in the C++ code
kalwalt Mar 31, 2024
16dd102
fix for getMatches function
kalwalt Mar 31, 2024
c78ef5c
fix for numMatches
kalwalt Mar 31, 2024
ef898c4
fix for numMatches format display
kalwalt Mar 31, 2024
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
2 changes: 2 additions & 0 deletions WebARKit/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ ${PARENT_DIR}/WebARKitTrackers/WebARKitOpticalTracking/include/WebARKitTrackers/
${PARENT_DIR}/include/WebARKitCamera.h
${PARENT_DIR}/include/WebARKitLog.h
${PARENT_DIR}/include/WebARKitManager.h
${PARENT_DIR}/include/WebARKitPattern.h
)

set(SOURCE
Expand All @@ -44,6 +45,7 @@ ${PARENT_DIR}/WebARKitTrackers/WebARKitOpticalTracking/WebARKitTracker.cpp
${PARENT_DIR}/WebARKitCamera.cpp
${PARENT_DIR}/WebARKitLog.cpp
${PARENT_DIR}/WebARKitManager.cpp
${PARENT_DIR}/WebARKitPattern.cpp
)

add_library(
Expand Down
4 changes: 4 additions & 0 deletions WebARKit/WebARKitManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,10 @@ std::vector<double> WebARKitManager::getOutputData() {
return m_tracker->getOutputData();
};

cv::Mat WebARKitManager::getPoseMatrix() {
return m_tracker->getPoseMatrix();
}

bool WebARKitManager::isValid() {
return m_tracker->isValid();
}
Expand Down
17 changes: 17 additions & 0 deletions WebARKit/WebARKitPattern.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
#include <WebARKitPattern.h>
#include <iostream>
#include <opencv2/calib3d.hpp>

void WebARKitPatternTrackingInfo::computePose(std::vector<cv::Point3f>& treeDPoints, std::vector<cv::Point2f>& imgPoints,
cv::Mat& caMatrix, cv::Mat& distCoeffs) {
cv::Mat rvec = cv::Mat::zeros(3, 1, CV_64FC1); // output rotation vector
cv::Mat tvec = cv::Mat::zeros(3, 1, CV_64FC1); // output translation vector

cv::solvePnPRansac(treeDPoints, imgPoints, caMatrix, distCoeffs, rvec, tvec);

cv::Mat rMat;
cv::Rodrigues(rvec, rMat);
cv::hconcat(rMat, tvec, pose3d);

std::cout << "pose3d: " << pose3d.rows << " x " << pose3d.cols << std::endl;
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,18 +7,21 @@ class WebARKitTracker::WebARKitTrackerImpl {
public:
WebARKitTrackerImpl()
: corners(4), initialized(false), output(17, 0.0), _valid(false), _isDetected(false), numMatches(0),
minNumMatches(MIN_NUM_MATCHES), _nn_match_ratio(0.7f){
m_camMatrix = cv::Mat();
m_distortionCoeff = cv::Mat();
};
minNumMatches(MIN_NUM_MATCHES), _nn_match_ratio(0.7f) {
m_camMatrix = cv::Mat();
//m_distortionCoeff = cv::Mat();
//_patternTrackingInfo.pose3d = cv::Mat::zeros(3, 4, CV_64FC1);
//m_distortionCoeff = cv::Mat::zeros(6, 1, CV_64FC1);
m_distortionCoeff = cv::Mat::zeros(4,1,cv::DataType<double>::type);
};

~WebARKitTrackerImpl() = default;

void initialize(webarkit::TRACKER_TYPE trackerType, int frameWidth, int frameHeight) {
setDetectorType(trackerType);
if (trackerType == webarkit::TEBLID_TRACKER) {
_nn_match_ratio = TEBLID_NN_MATCH_RATIO;
}
else if(trackerType == webarkit::AKAZE_TRACKER) {
} else if (trackerType == webarkit::AKAZE_TRACKER) {
_nn_match_ratio = DEFAULT_NN_MATCH_RATIO;
minNumMatches = 40;
} else {
Expand All @@ -27,8 +30,30 @@ class WebARKitTracker::WebARKitTrackerImpl {
}
_camera->setupCamera(frameWidth, frameHeight);
_camera->printSettings();
m_camMatrix = cv::Mat(3,3, CV_64FC1, _camera->getCameraData().data());
m_distortionCoeff = cv::Mat(6, 1, CV_64FC1, _camera->getDistortionCoefficients().data());
m_camMatrix = cv::Mat(3, 3, CV_64FC1, _camera->getCameraData().data());
/*m_camMatrix = cv::Mat(3, 3, CV_64FC1);
std::array<double, 9> camData = _camera->getCameraData();
for(auto i = 0; i < 3; i++) {
for(auto j = 0; j < 3; j++) {
//WEBARKIT_LOGi("Camera Matrix: %d\n", camData[i*3+j]);
m_camMatrix.at<double>(i, j) = camData[i*3+j];
}
}*/

for(auto i = 0; i < 3; i++) {
for(auto j = 0; j < 3; j++) {
WEBARKIT_LOGi("Camera Matrix: %.2f\n", m_camMatrix.at<double>(i, j));
}
}

for(auto i = 0; i < 6; i++) {
for(auto j = 0; j < 1; j++) {
WEBARKIT_LOGi("Distortion coefficients: %.2f\n", m_distortionCoeff.at<double>(i, j));
}
}

//m_distortionCoeff = cv::Mat(6, 1, CV_64FC1, _camera->getDistortionCoefficients().data());
//m_distortionCoeff = cv::Mat::zeros(6, 1, CV_64FC1);
}

void initTracker(uchar* refData, size_t refCols, size_t refRows) {
Expand All @@ -41,6 +66,29 @@ class WebARKitTracker::WebARKitTrackerImpl {
this->_featureDetector->detect(refGray, refKeyPts, trackerFeatureMask);
this->_featureDescriptor->compute(refGray, refKeyPts, refDescr);

// Normalized dimensions :
const float maxSize = std::max(refCols, refRows);
const float unitW = refCols / maxSize;
const float unitH = refRows / maxSize;

_pattern.size = cv::Size(refCols, refRows);

WEBARKIT_LOGd("WebARKitPattern size ready!\n");

_pattern.points2d.push_back(cv::Point2f(0, 0));
_pattern.points2d.push_back(cv::Point2f(refCols, 0));
_pattern.points2d.push_back(cv::Point2f(refCols, refRows));
_pattern.points2d.push_back(cv::Point2f(0, refRows));

WEBARKIT_LOGd("WebARKitPattern points2d ready!\n");

_pattern.points3d.push_back(cv::Point3f(-unitW, -unitH, 0));
_pattern.points3d.push_back(cv::Point3f(unitW, -unitH, 0));
_pattern.points3d.push_back(cv::Point3f(unitW, unitH, 0));
_pattern.points3d.push_back(cv::Point3f(-unitW, unitH, 0));

WEBARKIT_LOGd("WebARKitPattern points3d ready!\n");

corners[0] = cvPoint(0, 0);
corners[1] = cvPoint(refCols, 0);
corners[2] = cvPoint(refCols, refRows);
Expand Down Expand Up @@ -73,6 +121,8 @@ class WebARKitTracker::WebARKitTrackerImpl {

std::vector<double> getOutputData() { return output; };

cv::Mat getPoseMatrix() { return _patternTrackingInfo.pose3d; };

bool isValid() { return _valid; };

protected:
Expand Down Expand Up @@ -185,8 +235,18 @@ class WebARKitTracker::WebARKitTrackerImpl {

// set old points to new points
framePts = goodPtsCurr;
std::vector<cv::Point2f> warpedCorners;
//std::vector<cv::Point3f> treeDPoints;
if ((valid = homographyValid(m_H))) {
fill_output(m_H);
warpedCorners = getSelectedFeaturesWarped(m_H);
//treeDPoints = getSelectedFeatures3D(m_H);
if(m_camMatrix.empty()) {
WEBARKIT_LOGi("Camera Matrix is empty!\n");
}else {
WEBARKIT_LOGi("Camera Matrix: %d\n", m_camMatrix.at<double>(0, 0));
}
_patternTrackingInfo.computePose(_pattern.points3d, warpedCorners, m_camMatrix, m_distortionCoeff);
_isDetected = true;
} else {
_isDetected = false;
Expand Down Expand Up @@ -277,6 +337,14 @@ class WebARKitTracker::WebARKitTrackerImpl {
return featureMask;
}

std::vector<cv::Point2f> getSelectedFeaturesWarped(cv::Mat& H)
{
std::vector<cv::Point2f> warpedPoints;
perspectiveTransform(_pattern.points2d, warpedPoints, H);
WEBARKIT_LOGi("warpedPoint(0,0): %.2f, %.2f\n", warpedPoints[0].x, warpedPoints[0].y);
kalwalt marked this conversation as resolved.
Show resolved Hide resolved
return warpedPoints;
}

bool _valid;

bool _isDetected;
Expand All @@ -297,6 +365,10 @@ class WebARKitTracker::WebARKitTrackerImpl {

WebARKitCamera* _camera = new WebARKitCamera();

WebARKitPattern _pattern;

WebARKitPatternTrackingInfo _patternTrackingInfo;

cv::Mat m_camMatrix;
cv::Mat m_distortionCoeff;

Expand Down Expand Up @@ -333,7 +405,7 @@ class WebARKitTracker::WebARKitTrackerImpl {
this->_featureDescriptor = cv::ORB::create(DEFAULT_MAX_FEATURES);
} else if (trackerType == webarkit::TRACKER_TYPE::FREAK_TRACKER) {
this->_featureDetector = cv::ORB::create(10000);
//this->_featureDetector = cv::xfeatures2d::StarDetector::create(DEFAULT_MAX_FEATURES);
// this->_featureDetector = cv::xfeatures2d::StarDetector::create(DEFAULT_MAX_FEATURES);
this->_featureDescriptor = cv::xfeatures2d::FREAK::create();
} else if (trackerType == webarkit::TRACKER_TYPE::TEBLID_TRACKER) {
this->_featureDetector = cv::ORB::create(TEBLID_MAX_FEATURES);
Expand All @@ -351,7 +423,9 @@ WebARKitTracker::WebARKitTracker(WebARKitTracker&&) = default; // copy construct

WebARKitTracker& WebARKitTracker::operator=(WebARKitTracker&&) = default; // move assignment operator

void WebARKitTracker::initialize(webarkit::TRACKER_TYPE trackerType, int frameWidth, int frameHeight) { _trackerImpl->initialize(trackerType, frameWidth, frameHeight); }
void WebARKitTracker::initialize(webarkit::TRACKER_TYPE trackerType, int frameWidth, int frameHeight) {
_trackerImpl->initialize(trackerType, frameWidth, frameHeight);
}

void WebARKitTracker::initTracker(uchar* refData, size_t refCols, size_t refRows) {
_trackerImpl->initTracker(refData, refCols, refRows);
Expand All @@ -363,6 +437,8 @@ void WebARKitTracker::processFrameData(uchar* frameData, size_t frameCols, size_

std::vector<double> WebARKitTracker::getOutputData() { return _trackerImpl->getOutputData(); }

cv::Mat WebARKitTracker::getPoseMatrix() { return _trackerImpl->getPoseMatrix(); }

bool WebARKitTracker::isValid() { return _trackerImpl->isValid(); }

} // namespace webarkit
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include "WebARKitEnums.h"
#include <WebARKitLog.h>
#include <WebARKitCamera.h>
#include <WebARKitPattern.h>
#include <opencv2/xfeatures2d.hpp>

namespace webarkit {
Expand All @@ -26,6 +27,8 @@ class WebARKitTracker {

std::vector<double> getOutputData();

cv::Mat getPoseMatrix();

bool isValid();

private:
Expand Down
2 changes: 2 additions & 0 deletions WebARKit/include/WebARKitManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ class WebARKitManager {

std::vector<double> getOutputData();

cv::Mat getPoseMatrix();

bool isValid();
};

Expand Down
33 changes: 33 additions & 0 deletions WebARKit/include/WebARKitPattern.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
#ifndef WEBARKITPATTERN_H
#define WEBARKITPATTERN_H

#include <opencv2/core/core.hpp>

struct WebARKitPattern {
cv::Size size;

//cv::Mat grayImg;

//std::vector<cv::KeyPoint> keypoints;
//cv::Mat descriptors;

std::vector<cv::Point2f> points2d;
std::vector<cv::Point3f> points3d;
};

/**
* Intermediate pattern tracking info structure
*/
struct WebARKitPatternTrackingInfo
{
cv::Mat homography;
std::vector<cv::Point2f> points2d;
cv::Mat pose3d;

/**
* Compute pattern pose using PnP algorithm
*/
void computePose(std::vector<cv::Point3f>& treeDPoints, std::vector<cv::Point2f>& imgPoints, cv::Mat& caMatrix, cv::Mat& distCoeffs);
};

#endif // WEBARKITPATTERN_H
2 changes: 1 addition & 1 deletion tests/webarkit_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ TEST(WebARKitTest, InitTrackerTest) {
}

if(image.empty()) {
image = cv::Mat(2048, 1637, CV_8UC4, cv::Scalar(0, 0, 0, 0));
image = cv::Mat::zeros(2048, 1637, CV_8UC4);
}

ASSERT_FALSE(image.empty());
Expand Down