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

ORB extraction #283

Closed
jianchong-chen opened this issue Mar 17, 2017 · 17 comments
Closed

ORB extraction #283

jianchong-chen opened this issue Mar 17, 2017 · 17 comments

Comments

@jianchong-chen
Copy link

I found 2 issues in orb extraction when I used it in another project.

  1. it will crash in DistributeOctTree(nIni = 0) if the image width is smaller than height
  2. The results are always different for several times feature extraction with a same image, but I don't find anywhere used random variation.
@AlejandroSilvestri
Copy link

RANSAC uses random seeds. And RanSaC is used everywhere.

Initialization process involves some randomness too.

@jianchong-chen
Copy link
Author

Hi AlejandroSilvestri, thanks for your help.
But what I used is only the class ORBextractor, and I reviewed the code again. There is no RANSAC used in this class.
I'm not sure whether I made some mistakes, if so I wonder why RANSAC is needed in the feature extraction and could you give some reference documents. Thanks again!
the test code is as follows:
ORBextractor orb(1000);
orb(m, noArray(), keypoints, descriptor);
printf("orb1: %d\n", keypoints.size());
orb(m, noArray(), keypoints, descriptor);
printf("orb2: %d\n", keypoints.size());
while the results are:
==============frame 0==============
orb1: 1001
orb2: 1002
==============frame 1==============
orb1: 1007
orb2: 1004
==============frame 2==============
orb1: 1003
orb2: 1006

@AlejandroSilvestri
Copy link

Ok. I'm trying to locate the reason.

I'm reading your code. What is ORBextractor orb(1000) ? I couldn't find this constructor in ORB-SLAM2. Please point me to the file and line.

The code would be cleaner if you repeat the extraction on a new ORBextractor instance, so it guarantees same initial conditions. Let's say, repeat ORBextractor orb(1000) after the first printf.

@jianchong-chen
Copy link
Author

I'm sorry I forgot to say that I changed the ORBextractor constructor to

ORBextractor(int _nfeatures, float _scaleFactor = 1.2f, int _nlevels = 8, int _nfirstLevel = -1, 
	     int _iniThFAST = 20, int _minThFAST = 7);

I rewrite the test code with the original ORBextractor as follows:

vector<KeyPoint> keypoints;
Mat descriptor;
Mat m = imread("D:/4-dataset/1.jpg");
for (int i = 0; i < 20; i++)
{
	keypoints.clear();
	ORBextractor orb(1000, 1.2f, 8, 20, 7);
	orb(m, noArray(), keypoints, descriptor);
	printf("%d kepoints: %d\n", i, keypoints.size());
}

And the output is

0 kepoints: 1006
1 kepoints: 1005
2 kepoints: 1006
3 kepoints: 1003
4 kepoints: 1006
5 kepoints: 1004
6 kepoints: 1005
7 kepoints: 1006
8 kepoints: 1003
9 kepoints: 1002
10 kepoints: 1003
11 kepoints: 1004
12 kepoints: 1006
13 kepoints: 1004
14 kepoints: 1005
15 kepoints: 1004
16 kepoints: 1004
17 kepoints: 1004
18 kepoints: 1003
19 kepoints: 1005

The resluts are still different even I initialize the extractor each time.

@AlejandroSilvestri
Copy link

@jcchen1987 , in other experiments I noticed FAST has that behavior, I don't know why, I guess non-max suppression can do that if FAST divide its tasks in many parallel threads.

I believe parallel threads include some randomness in the time they take to complete their task, because the OS control them, not the application.

@jianchong-chen
Copy link
Author

@AlejandroSilvestri, your suppose is very likely to be right, I will check it later. Thanks for you help!

@kerolex
Copy link

kerolex commented Sep 30, 2017

Sorry to re-open this issue, but I was analysing the same.

I am not fully convinced by the multi-thread of FAST as I haven not found any thread in the OpenCV implementation. Moreover, if it was so, even the normal ORB implementation of OpenCV should show a similar behaviour. In my opinion, this behaviour seems occurring inside the octree detections.

I will further check such a behaviour, but if you have found something, please let me know.
Thanks.

@kerolex
Copy link

kerolex commented Oct 19, 2017

The weird behaviour is caused by std::sort within the DistributeOctTree( ) function along with lNodes.size()>=N condition inside the nested while (ORBextractor.cpp):
vector<cv::KeyPoint> ORBextractor::DistributeOctTree(..
...
while(!bFinish) { iteration++;
...
else if(((int)lNodes.size()+nToExpand*3)>N) { while(!bFinish) {
...
sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end()); // Line 684
...
if((int)lNodes.size()>=N) {break;} \\ line 730

When there are nodes with same number of features, sort randomly orders equivalent values and it happens that the if condition breaks the for loop exactly between two nodes (different cells) with same number of features, which can be ordered differently over multiple runs inside a program. This generates results with swapped key-points at different position and some more (or less) key-points. However, running a bash script that calls multiple times the ORB extractor generates the same results as the random seed within sort is re-initialise.

The suggestions and current solution I am using is to change std::sort with std::stable_sort from the <algorithm> container. The stable_sort can ba called with a third argument that is a user-defined function to determine the order between two equivalent (but not equal) elements. As ORB-SLAM is ordering a vector of pairs <nFeatures, Node*>, we can write a LessThanComparable function (see example) that compares the x coordinates of the upper-left corner of the nodes (cell) and thus selects first the node with lower value of the coordinate when the number of features is equal.

Here, my current working solution:
#include <algorithm.h>
...
static bool cornerComparison(pair<int,ExtractorNode*> a, pair<int,ExtractorNode*> b)
{ return (a.second->UL.x < b.second->UL.x); }
and replace line 684 with
std::stable_sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end(), cornerComparison);

Please let me know if there is something not clear in the explanation.
Thanks.

@AlejandroSilvestri
Copy link

@kerolex ,

Thank you for the neat explanation. Believe it or not, I was worry about not understanding this weird behaviour.

Now I have to understand why sort operates randomly on equivalent values, on the exactly same data. And this behaviour can vary on different implementations of std::sort. But this is way beyond orb-slam2 scope.

@kerolex
Copy link

kerolex commented Oct 19, 2017

@AlejandroSilvestri,

from my knowledge and understanding, I think that sort repeats exactly the same elements on the same data if called within a bash script (you call the ORBextractor only once for that program run), because of the seed in rng. This is not longer true if you called it twice within the program as the random generator has a different seed (probably depending on the elapsing time).

@AlejandroSilvestri
Copy link

@kerolex ,

Where does that ramdom generator take place? In std::sort or in orb-slam2 code?
There is a random generator or it's a guess?

@kerolex
Copy link

kerolex commented Oct 19, 2017

@AlejandroSilvestri ,

Sorry, I replied quickly earlier.

From the current behaviour, I guess there is a seed inside std::sort, otherwise I cannot explain to myself why it can generate the same order with a bash script. So, I do not know if there is really a random generator inside sort.

@AlejandroSilvestri
Copy link

@kerolex ,

I don't believe there is a random generator in sort, but your findings are enlightening.

@Shar-pei-bear
Copy link

Shar-pei-bear commented May 13, 2020

@jianchong-chen Hi jianchong, for the problem that orb extraction will crash in DistributeOctTree(nIni = 0) if the image width is smaller than height, could you share your solution? I am having the same problem. Thank you.

@jianchong-chen
Copy link
Author

@Shar-pei-bear
One way to fix the bug is to change the nIni to be 1(const int nIni = 1;), the result is a little different from the original algrithm, but I think it is ok for application.
And I re-wrote the code to split keypoints with quad-tree. I can share to you if you need.

@jianchong-chen Hi jianchong, for the problem that orb extraction will crash in DistributeOctTree(nIni = 0) if the image width is smaller than height, could you share your solution? I am having the same problem. Thank you.

@Shar-pei-bear
Copy link

@Shar-pei-bear
One way to fix the bug is to change the nIni to be 1(const int nIni = 1;), the result is a little different from the original algrithm, but I think it is ok for application.
And I re-wrote the code to split keypoints with quad-tree. I can share to you if you need.

@jianchong-chen Hi jianchong, for the problem that orb extraction will crash in DistributeOctTree(nIni = 0) if the image width is smaller than height, could you share your solution? I am having the same problem. Thank you.

@jianchong-chen Hi jianchong, sorry to respond so late. I managed to come up with a fix: github repo. I would love to read your solution to this problem.

@jianchong-chen
Copy link
Author

I rewrite the code to filter the keypoints with quad-tree.
I find the min rect for the keypoints, and then split to 4 parts recursively.
The code is as follow.

struct QuadTreeNode
{
	cv::Rect2f rgn;
	vector<cv::KeyPoint> key_points;
	bool stop_split;
	bool Split(vector<QuadTreeNode> &split_nodes)
	{
		if (stop_split)
		{
			split_nodes.clear();
			split_nodes.emplace_back(*this);
			return false;
		}
		float x = rgn.x;
		float y = rgn.y;
		float cx = rgn.x + rgn.width / 2;
		float cy = rgn.y + rgn.height / 2;
		float half_w = rgn.width * 0.5f;
		float half_h = rgn.height * 0.5f;
		//1 node split to 4 nodes
		//       0 | 1
		//       -----
		//       2 | 3
		split_nodes.resize(4);
		split_nodes[0].rgn = cv::Rect(x, y, half_w, half_h);
		split_nodes[1].rgn = cv::Rect(cx, y, half_w, half_h);
		split_nodes[2].rgn = cv::Rect(x, cy, half_w, half_h);
		split_nodes[3].rgn = cv::Rect(cx, cy, half_w, half_h);
		for (int i = 0; i < 4; i++) split_nodes[i].key_points.reserve(key_points.size());
		for (int i = 0; i < key_points.size(); ++i)
		{
			float &cur_x = key_points[i].pt.x;
			float &cur_y = key_points[i].pt.y;
			int id = ((cur_y > cy) << 1) | (cur_x > cx);
			split_nodes[id].key_points.emplace_back(key_points[i]);
		}
		auto it = split_nodes.begin();
		while (it != split_nodes.end())
		{
			if (it->key_points.empty()) it = split_nodes.erase(it);
			else
			{
				it->UpdateSplitStatus();
				it++;
			}
		}
		return !split_nodes.empty();
	}
	void UpdateSplitStatus()
	{
		if (rgn.width <= 1 || rgn.height <= 1 || key_points.size() == 1) stop_split = true;
		else stop_split = false;
	}
};

static void QuadSplitKeyPoints(vector<KeyPoint> &key_points, int n)
{
	if (key_points.empty() || key_points.size() <= n) return;
	float min_x, min_y, max_x, max_y;
	min_x = max_x = key_points[0].pt.x;
	min_y = max_y = key_points[0].pt.y;
	for (int i = 0; i < key_points.size(); i++)
	{
		float &x = key_points[i].pt.x;
		float &y = key_points[i].pt.y;
		min_x = MIN(min_x, x);
		max_x = MAX(max_x, x);
		min_y = MIN(min_y, y);
		max_y = MAX(max_y, y);
	}

	std::vector<QuadTreeNode> cur_nodes(1);
	cur_nodes[0].rgn = cv::Rect(min_x, min_y, max_x - min_x, max_y - min_y);
	cur_nodes[0].key_points.swap(key_points);
	cur_nodes[0].UpdateSplitStatus();

	while (cur_nodes.size() < n)
	{
		bool stop = true;
		std::vector<QuadTreeNode> all_split_node;
		all_split_node.reserve(cur_nodes.size() * 4);
		for (int i = 0; i < cur_nodes.size(); i++)
		{
			std::vector<QuadTreeNode> split_node;
			bool split_success = cur_nodes[i].Split(split_node);
			all_split_node.insert(all_split_node.end(), split_node.begin(), split_node.end());
			if (split_success) stop = false;
			if (all_split_node.size() + cur_nodes.size() - i - 1 >= n)
			{
				stop = true;
				all_split_node.insert(all_split_node.end(), cur_nodes.begin() + i + 1, cur_nodes.end());
				break;
			}
		}
		cur_nodes.swap(all_split_node);
		if (stop) break;
	}
	key_points.clear();
	key_points.reserve(cur_nodes.size());
	for (int i = 0; i < cur_nodes.size(); i++)
	{
		std::vector<cv::KeyPoint> &cur_key_points = cur_nodes[i].key_points;
		if (cur_key_points.empty()) continue;
		float max_response_idx = 0;
		for (int j = 1; j < cur_key_points.size(); j++)
		{
			if (cur_key_points[j].response > cur_key_points[max_response_idx].response) max_response_idx = j;
		}
		key_points.emplace_back(cur_key_points[max_response_idx]);
	}
}

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants