ORB_SLAM3 icon indicating copy to clipboard operation
ORB_SLAM3 copied to clipboard

Find keypoints in source for a mask implementation

Open Styazoua opened this issue 1 year ago • 2 comments

Hello,

I am trying to implement the use of a mask where I want do drop detected keypoints which are inside of the defined mask For testing I created mask with size of my image. I filled half of the mask with 0 and the other half != 0.

The code below is an implementation in ORBextractor.cc inside ORBextractor::ComputeKeyPointsOctTree() Here for I'm taking the points from vKeysCell which are the output from the FAST corner detector.

When the frame gets displayed the whole image if full of keypoints. My expectation was only half of the frame. I am not sure if I'm checking at the correct position. Can someone help here? Thank you

FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),vKeysCell,iniThFAST,true);
void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints, const cv::Mat &mask)
    {
        allKeypoints.resize(nlevels);

        const float W = 35;

        for (int level = 0; level < nlevels; ++level)
        {
            const int minBorderX = EDGE_THRESHOLD-3;
            const int minBorderY = minBorderX;
            const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
            const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;


            vector<cv::KeyPoint> vToDistributeKeys;
            vector<vector<KeyPoint> > tmpAllKeypoints;
            vector<KeyPoint> tmpKeypoint;
            vToDistributeKeys.reserve(nfeatures*10);

            const float width = (maxBorderX-minBorderX);
            const float height = (maxBorderY-minBorderY);

            const int nCols = width/W;
            const int nRows = height/W;
            const int wCell = ceil(width/nCols);
            const int hCell = ceil(height/nRows);

            for(int i=0; i<nRows; i++)
            {
                const float iniY =minBorderY+i*hCell;
                float maxY = iniY+hCell+6;

                if(iniY>=maxBorderY-3)
                    continue;
                if(maxY>maxBorderY)
                    maxY = maxBorderY;

                for(int j=0; j<nCols; j++)
                {
                    const float iniX =minBorderX+j*wCell;
                    float maxX = iniX+wCell+6;
                    if(iniX>=maxBorderX-6)
                        continue;
                    if(maxX>maxBorderX)
                        maxX = maxBorderX;

                    vector<cv::KeyPoint> vKeysCell;

                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,iniThFAST,true);


                    if(vKeysCell.empty())
                    {
                        FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                             vKeysCell,minThFAST,true);
                    }


//################################################################################


                    if(!vKeysCell.empty())
                    {
                        for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                        {
                            (*vit).pt.x+=j*wCell;
                            (*vit).pt.y+=i*hCell;

                            if(mask.empty())
                            {
                                vToDistributeKeys.push_back(*vit);
                            }
                            else
                            {
                                // check value of mask cell with coords of keypoint
                                int value = mask.at<int>((*vit).pt.y, (*vit).pt.x);
                                if(value == 0)
                                {
                                    cout << "Point not inside mask. Value = " << value << endl;
                                    cout << "vKeysCell size: " << vKeysCell.size() << endl;
                                    cout << "Position of point: (" << (*vit).pt.x << "/" << (*vit).pt.y << ")" << endl;
                                    vToDistributeKeys.push_back(*vit);
                                }
                                else
                                {
                                    cout << "Removing point. Point inside mask. Value = " << value << endl;
                                    cout << "Position of point: (" << (*vit).pt.x << "/" << (*vit).pt.y << ")" << endl;
                                }
                            }
                        }
                    }

                }
            }



//################################################################################

            vector<KeyPoint> & keypoints = allKeypoints[level];
            keypoints.reserve(nfeatures);

            keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
                                          minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);

            const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

            // Add border to coordinates and scale information
            const int nkps = keypoints.size();
            for(int i=0; i<nkps ; i++)
            {
                keypoints[i].pt.x+=minBorderX;
                keypoints[i].pt.y+=minBorderY;
                keypoints[i].octave=level;
                keypoints[i].size = scaledPatchSize;
            }
        }

        // compute orientations
        for (int level = 0; level < nlevels; ++level)
            computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
    }

Styazoua avatar Jan 19 '24 13:01 Styazoua

Here is also a part of the console output. I'm not sure if its all correct but at least some keypoints should be removed.

Point not inside mask. Value = 0
vKeysCell size: 16
Position of point: (962/339)
Removing point. Point inside mask. Value = -1
Position of point: (951/340)
Removing point. Point inside mask. Value = -1
Position of point: (944/341)
Removing point. Point inside mask. Value = -1
Position of point: (956/341)
Point not inside mask. Value = 0
vKeysCell size: 16
Position of point: (960/341)
Removing point. Point inside mask. Value = -1
Position of point: (947/342)
Point not inside mask. Value = 0
vKeysCell size: 16
Position of point: (973/344)
Point not inside mask. Value = 0
vKeysCell size: 16
Position of point: (960/350)
Point not inside mask. Value = 0
vKeysCell size: 16
Position of point: (963/361)

Styazoua avatar Jan 19 '24 13:01 Styazoua

That's what I'm doing at the moment. I'm passing the mask over this argument. Inside of operator() my modified ComputeKeyPointsOctTree() function gets called. But unfortunatelly it's not working.

Styazoua avatar Jan 19 '24 14:01 Styazoua