introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.74k stars 779 forks source link

How to setFeatures() in SensorData? #1044

Closed borongyuan closed 1 year ago

borongyuan commented 1 year ago

DepthAI has a FeatureTracker node for feature detection and tracking. So I took a look to see if it is possible to directly add features to SensorData. Then I found that there is indeed a setFeatures() method, which accepts 3 inputs. It looks like not all 3 items are required. So I'm trying to understand how this should be used? What is the effect of different combinations of inputs?

Specifically, FeatureTracker just does Harris or Shi-Tomasi (GFTT) corner detection. Therefore only 2D keypoints can be provided. The last 2 inputs are empty. Is this going to work? Will subsequent programs calculate descriptors for these detected points? Do I need to modify other parts of the code or parameters?

Also, some people are trying to run SuperPoint directly on OAK camera. It would be very helpful if this worked.

borongyuan commented 1 year ago

I created a new repository to test superpoint on OAK camera. I haven't decoded the inference results yet, just to roughly evaluate the performance first. When the StereoDepth node is enabled, 10 of the 16 shave cores are available for NeuralNetwork nodes. So I compile the model for 10 shaves (single thread) or 5 shaves (2 threads). The inference time for 320x200 input is about 63ms using single thread. This means we can run superpoint on the OAK camera at least at 15FPS. We can also use 2 threads to get higher FPS, at the cost of higher latency.

matlabbe commented 1 year ago

It is very interesting that SuperPoint could run on device. For this function: https://github.com/introlab/rtabmap/blob/af481fc73074ae13faaa08511ee6d5e36e805b65/corelib/include/rtabmap/core/SensorData.h#L273

The arguments are in order of priority.

Notes:

  1. In localization mode with Vis/EstimationType=1 (default PnP), 3D keypoints vector is not required, but recommended to get better covariance estimation.
  2. If all 3 are provided in SensorData, you don't need to stream the image data, unless occupancy grid is required downstream. Well, you could provide local occupancy grid in SensorData so that raw data is not needed.
borongyuan commented 1 year ago

Hi, I have added superpoint heatmap visualization in the example, looks good. https://github.com/borongyuan/depthai-superpoint 2023-06-10 17-50-08屏幕截图