陪你讀論文 - 3D Multi-Object Tracking: A Baseline and New Evaluation Metrics (IROS 2020)


前言

自從寫 Leetcode 刷題 pattern 系列以來,已經有點久沒有寫論文的 summary 文章了,從前陣子開始寫 3D Deep Learning 入門(一)- Deep learning on regular structures 提到一些 paper,這次再延伸一下,完整來讀一篇 IROS 2020 的論文 - 3D Multi-Object Tracking: A Baseline and New Evaluation Metrics

之所以選擇這篇論文,是因為這篇具有設立 3D Multi-Object Tracking(以下簡稱 3D MOT)新的 benchmark metrics、並提出新 baseline 的代表意義,懂了這篇,就可以把這篇提出的 metrics 和 baseline 方法當作基礎,開發更厲害的 3D MOT 演算法。

3D MOT 問題是什麼

在開始讀論文前,我們先瞭解一下什麼是 3D MOT。3D MOT 就是輸入 3D data(也可以加上 image,看系統的設計),辨識出 3D data 中的 moving object,得到這些 object 的 bounding box,並持續追蹤這些 moving object:

3D MOT

在理解了 3D MOT 問題之後,我們來看看基本的 3D MOT pipeline:

  1. Sensor Data:這一步就是輸入 input,應該不必多說

  2. 3D Object detection

    有了 sensor data 之後,我們可以對這些 data 做 object detection,得到一堆 3D bounding box。

  3. Data association

    雖然上一步得到了 3D bounding box,但我們要做 tracking,就必須把不同 frame 偵測到的同一個物體 bounding box 用某種辦法判斷為同一物體,這就是 data association。

  4. Evaluation

    最後,我們要評測提出的 3D MOT 演算法夠不夠好。

看完這面的簡單說明,大家應該已經對 3D MOT 問題有了基本的認識,接下來,我們可以開始來看這篇論文想要解決的問題啦!

要解決的問題

這篇論文想要解決兩個問題:

  1. 現今的 SOTA(State-Of-The-Art) MOT 演算法大多都沒有考慮實際應用的需求,例如不能計算太久。而且也常常設計得很複雜,所以不確定到底是哪個 module 對 performance 貢獻最大。當然,先把追求 accuracy 做好是可以理解,但也許該是時候把 real-time 應用也考慮進來。
  2. 3D MOT 的評測方法不夠好。例如 KITTI 在比較 3D MOT 時,會先把 3D bounding box 投影到 image plane,然後再計算 IOU,但這樣就已經喪失了 3D 資訊,看下圖就能了解這樣做在某些情況下不準:

所以這篇論文針對上面的兩個問題,做出了三點主要的貢獻:

  1. 提出新的 3D MOT baseline(能做到 207 fps,且 accuracy 不輸其他 SOTA 方法)
  2. 提出了在 3D space 比較 3D MOT 演算法的方法
  3. 提出了三種新的 metrics,能對 3D MOT 演算法有更全面的評測

以下我們就根據這三點貢獻,來仔細說明一下。

新的 3D MOT baseline - AB3DMOT

這個 baseline 方法簡稱 AB3DMOT(A Baseline for 3D MOT),先來看一下他的架構圖:

因為他每個部分的作法都相對簡單,所以我就直接條列說明:

  1. 3D Object Detection:他們直接使用已經 train 好的現成 model,例如 PointRCNNMono3DPLiDAR。這階段的 output 是 (x,y,z,θ,l,w,h,s),其中 (x, y, z) 就是 3D bounding box 的位置、θ 是 box 的 orientation(或說是 yaw,因為我們只關心 yaw),(l,w,h) 是長寬高、最後 s 是 confidence score。
  2. 3D Kalman filter - prediction 部分:這邊的 state vector 是一個 11 維的 vector (x,y,z,θ,l,w,h,s,vx,vy,vz),然後為了維持簡單,他們假設 tracking 到的物體(以下就簡稱 track)是用 constant velocity 在移動,而且不考慮 ego motion。這個假設雖然過於簡化,但因為這篇論文的重點是提出足夠好的 baseline 方法,所以這個設計我覺得合理。(還可以看看這篇討論 - Ego motion is not considered
  3. Data association:有了前兩步,我們在新的 frame 就會有一群剛偵測到的 box(觀測值)、以及從上一個 frame 預測得到的 box(預測值),這邊會先根據兩兩 box 之間的 3D IOU 或中心點的距離來建立 affinity matrix,把問題變成一個 bipartite graph matching problem(演算法課程的經典問題之一)。接著用 Hungarian algorithm 來 match 兩群 box。如果 matched boxes 彼此之間的 3D IOU 太小,就會被視為不 match。
  4. 3D Kalman filter - update 部分:有了預測值跟 match 到的觀測值,我們就可以 update tracking object 的 state,至於預測值跟觀測值之間的權重怎麼選,有興趣的人就自行去研究一下 Kalman filter 吧。
  5. Birth and Death memory:隨著汽車的行進,一定會有一些物體脫離視線、有一些新的物體進入視線,所以需要控管哪些 track 已經結束、哪些 track 要新增。這邊為了避免因為偶爾偵測不到,所以 track 必須要有一段時間都 match 不到 3D detection box,才會被移出 memory,而新增的 track 必須要持續出現一段時間,才會被加入 memory。

瞭解這個方法後,是不是覺得很直觀呢?接著就讓我們繼續看下去。

在 3D space 比較 3D MOT 演算法的方法

這邊沒有太特別的地方,主要就是實作了 3D IOU,所以 3DMOT 演算法產生出來的 box 若要被認定為跟 ground truth 是 match,就要有足夠高的 3D IOU,另外中心點距離也不能太遠。

程式碼可以看 這邊,我截出 3D IOU function 給大家看看:

def iou3d(corners1, corners2):
    ''' Compute 3D bounding box IoU, only working for object parallel to ground
    Input:
        corners1: numpy array (8,3), assume up direction is negative Y
        corners2: numpy array (8,3), assume up direction is negative Y
    Output:
        iou: 3D bounding box IoU
        iou_2d: bird's eye view 2D bounding box IoU
    todo (rqi): add more description on corner points' orders.
    '''
    # corner points are in counter clockwise order
    rect1 = [(corners1[i,0], corners1[i,2]) for i in range(3,-1,-1)]
    rect2 = [(corners2[i,0], corners2[i,2]) for i in range(3,-1,-1)] 
    area1 = poly_area(np.array(rect1)[:,0], np.array(rect1)[:,1])
    area2 = poly_area(np.array(rect2)[:,0], np.array(rect2)[:,1])

    _, inter_area = convex_hull_intersection(rect1, rect2)

    iou_2d = inter_area/(area1+area2-inter_area)
    ymax = min(corners1[0,1], corners2[0,1])
    ymin = max(corners1[4,1], corners2[4,1])
    inter_vol = inter_area * max(0.0, ymax-ymin)
    vol1 = box3d_vol(corners1)
    vol2 = box3d_vol(corners2)
    iou = inter_vol / (vol1 + vol2 - inter_vol)
    return iou, iou_2d

我沒有仔細研究這邊的計算,只知道基本概念是假設兩個 box 都跟地面平行,先找出 2D 平面上的交集面積,乘上 box 的高度就是 3D 交集面積。我有找到看起來不錯的圖跟步驟說明(出自 3D-GIoU: 3D Generalized Intersection over Union for Object Detection in Point Cloud),之後有需要再來仔細研究(如果你需要弄懂,可以仔細讀 convex_hull_intersection()):

三種新的 metrics

我們要先了解 現有 metrics 的問題,才能夠真正理解為何這篇論文要再提出新的 metrics,我們直接用下圖來說明:

我們知道,3D detection module 吐出的 box 是有 confidence score 的,所以如何決定 confidence score 的 threshold 就很重要。如果 threshold 訂得太低,就會有太多不正確的 box 被保留,recall 會很高,就是上圖 (a) 裡面,有太多 False Positive(FP)的情況;而如果 threshold 訂得太高,就會有太多正確的 box 被丟掉,recall 會很低,就是上圖 (b) 裡面,False Negative(FN)太多。而從 (c) 來看,可以很清楚看到,把 threshold 訂在 recall 大約為 0.9 的地方,可以得到最高的 MOTA。而只看這最高點的 MOTA 也是過去各 paper 的主要比較方法。

但我們可以發現,這樣做的問題不少,一方面你得手動 tune confidence threshold 直到拿到最高的 MOTA(而且如果你換了一個 3D object detector,你就得重新 tune),另一方面也許 A 方法的最高點很高,但其他點不高,而 B 方法的最高點沒有 A 高,但平均來說比較高,這樣我們能說 A 就一定是最好的方法嗎?這似乎怪怪的。所以,作者才提出了新的 metrics。

AMOTA(Average MOTA)

AMOTA 就是 MOTA curve 下的平均面積,滿直觀的,直接上公式:

其中 IDS 表示 ID switch,代表同一個 object,被 3DMOT 系統在不同時間認為是不同物體,所以也算是一種錯誤。

AMOTP

概念上跟 AMOTA 一樣,只是算的對象變成 MOTP。如果你不知道 MOTP 是什麼,讓我放個出自 原 paper 的截圖:

一言以蔽之,MOTA 越高,表示越少 FP、FN(misses)還有 mismatch,也就是越能精準追蹤到所有該追蹤的物體、越不會追蹤到不該追蹤到的物體、越不會搞錯物體。

而 MOTP 越高,表示 match 到的物體位置越準確。

sAMOTA

sAMOTA 我有點懶得詳細說明,基本上就是為了讓比較 MOT 系統的表現時,能夠有更明顯的差距,所以會希望 percentage 的範圍是從 0% ~ 100%,但因為 MOTA 本身有 upper bound,就達不到 0% ~ 100% 這個願望。所以他們調整了一下,產生 sMOTA,而 sMOTA 的範圍就是 0% ~ 100%。概念上就只是讓表現好跟表現差的方法,能在 percentage 上有更顯著的差異。

結果

我們來看 AB3DMOT 跟其他 SOTA 方法的比較:

其中箭頭向上的 metric 表示越高越好,可以很明顯地看出 AB3DMOT 在 KITTI dataset 的表現完全不輸其他 SOTA 的方法,而且 inference speed 是爆表的 207 fps(而且還是用 CPU lol)。

作者還有做 ablation study(一種研究方法,透過一次更改一個 module 或設置,去了解系統中各 module 或參數對表現的影響),不過我覺得不需要再額外說明,有興趣的讀者可以自己去看 paper。

總結

今天用一篇文章帶大家看了一篇 3D MOT 領域的論文,相信從裡面提出的解法,跟它才出來沒多久就已經被引用快 50 次,都能感受到是一篇重要的標準設立型論文,之後有機會再來介紹其他 SOTA 的演算法,或介紹如何使用這篇論文的 code

如果你比較喜歡看影片,也可以去看看作者的 IROS talk(點擊下面的 gif 圖就可以連結到影片),我覺得講得非常清楚。See you next month!

15 minute oral presentation at IROS 2020

延伸閱讀

  1. Github repo: awesome-3d-multi-object-tracking
#3D Multi-Object Tracker #Self-Driving Car







你可能感興趣的文章

【隨堂筆記】Python 桌面應用程式

【隨堂筆記】Python 桌面應用程式

CSS - Flexbox

CSS - Flexbox

 5.字串比較

5.字串比較






留言討論