Main Content

このページの内容は最新ではありません。最新版の英語を参照するには、ここをクリックします。

PointSeg 深層学習ネットワークを使用した LIDAR 点群のセマンティック セグメンテーション

この例では、オーガナイズド 3 次元 LiDAR 点群データで PointSeg セマンティック セグメンテーション ネットワークに学習させる方法を示します。

PointSeg [1] は、オーガナイズド LiDAR 点群に基づく道路オブジェクトに対してエンドツーエンドのセマンティック セグメンテーションを実行するための畳み込みニューラル ネットワーク (CNN) です。Atrous Spatial Pyramid Pooling (ASPP) や Squeeze-and-Excitation ブロックなどの手法を使用することにより、ネットワークは改善されたセグメンテーション結果を提供します。この例に示す学習手順では、深層学習ネットワークへの入力として 2 次元球面投影イメージが必要です。

この例では、Ouster OS1 センサーを使用して収集されたハイウェイのシーンのデータ セットを使用します。これには、ハイウェイのシーンのオーガナイズド LiDAR 点群スキャンと、自動車やトラックのオブジェクトの対応するグラウンド トゥルース ラベルが含まれています。データ ファイルのサイズは約 760 MB です。

LIDAR データ セットのダウンロード

次のコードを実行して、ハイウェイのシーンのデータ セットをダウンロードします。データ セットには 1617 の点群が含まれており、cell 配列内の pointCloud オブジェクトとして格納されています。例に添付されている対応するグラウンド トゥルース データには、各点群内の自動車とトラックの境界ボックス情報が含まれています。

url = 'https://www.mathworks.com/supportfiles/lidar/data/WPI_LidarData.tar.gz';

outputFolder = fullfile(tempdir,'WPI');
lidarDataTarFile = fullfile(outputFolder,'WPI_LidarData.tar.gz');

if ~exist(lidarDataTarFile, 'file') 
    mkdir(outputFolder);
    
    disp('Downloading WPI Lidar driving data (760 MB)...');
    websave(lidarDataTarFile, url);
    untar(lidarDataTarFile,outputFolder); 
end

% Check if tar.gz file is downloaded, but not uncompressed.
if ~exist(fullfile(outputFolder, 'WPI_LidarData.mat'), 'file')
    untar(lidarDataTarFile,outputFolder);
end
lidarData = load(fullfile(outputFolder, 'WPI_LidarData.mat'));

groundTruthData = load('WPI_LidarGroundTruth.mat');

メモ: インターネット接続の速度によっては、ダウンロード プロセスに時間がかかることがあります。このコードは、ダウンロード プロセスが完了するまで、MATLAB® の実行を一時停止します。または、Web ブラウザーを使用してデータ セットをローカル ディスクにダウンロードした後、WPI_LidarData を抽出することもできます。Web からダウンロードしたファイルを使用するには、コード内の変数 outputFolder をダウンロードしたファイルの場所に変更します。

事前学習済みのネットワークのダウンロード

学習の完了を待たなくて済むように、事前学習済みのネットワークをダウンロードします。ネットワークに学習させる場合は、変数 doTraining を true に設定します。

doTraining = false;
if ~doTraining && ~exist('trainedPointSegNet.mat','file')
    disp('Downloading pretrained network (14 MB)...');
    pretrainedURL = 'https://www.mathworks.com/supportfiles/lidar/data/trainedPointSegNet.mat';
    websave('trainedPointSegNet.mat', pretrainedURL);
end
Downloading pretrained network (14 MB)...

学習用データの準備

LIDAR 点群とクラス ラベルの読み込み

この例に添付されているサポート関数 helperGenerateTrainingData を使用して、LIDAR 点群から学習データを生成します。この関数は、点群と境界ボックスのデータを使用して、5 チャネルの入力イメージとピクセル ラベル イメージを作成します。ピクセル ラベル イメージを作成するために、関数は境界ボックス内の点を選択して、境界ボックスのクラス ID でそれらにラベルを付けます。各学習イメージは、次の 64 x 1024 x 5 の配列として指定されます。

  • 各イメージの高さは 64 ピクセル。

  • 各イメージの幅は 1024 ピクセル。

  • 各イメージには 5 つのチャネルがあります。5 つのチャネルは、点群の 3 次元座標、強度、および範囲を r=x2 +y2+z2 で指定します。

学習データの視覚的表現は次のようになります。

LidarImage.png

5 チャネルの学習イメージとピクセル ラベル イメージを生成します。

imagesFolder = fullfile(outputFolder, 'images');
labelsFolder = fullfile(outputFolder, 'labels');

helperGenerateTrainingData(lidarData, groundTruthData, imagesFolder, labelsFolder); 
Preprocessing data 100.00% complete

5 チャネルのイメージは MAT ファイルとして保存されます。ピクセル ラベルは PNG ファイルとして保存されます。

メモ: 処理には時間がかかる場合があります。このコードは、処理が完了するまで MATLAB® の実行を一時停止します。

ImageDatastore と PixelLabelDatastore の作成

imageDatastoreオブジェクトを使用し、カスタム MAT ファイル リーダーであるサポート関数 helperImageMatReader を使用して、2 次元球面イメージの 5 つのチャネルを抽出して保存します。関数は、サポート ファイルとしてこの例に添付されています。

imds = imageDatastore(imagesFolder, ...
         'FileExtensions', '.mat', ...
         'ReadFcn', @helperImageMatReader);

pixelLabelDatastore (Computer Vision Toolbox)オブジェクトを使用して、ラベル イメージからピクセル単位のラベルを保存します。オブジェクトは、各ピクセル ラベルをクラス名にマッピングします。この例では、自動車とトラックのみを対象オブジェクトとし、他のすべてのピクセルは背景とします。それらのクラス (自動車、トラック、背景) を指定し、各クラスに一意のラベル ID を割り当てます。

classNames = [
    "background"
    "car"
    "truck"
];

numClasses = numel(classNames);

% Specify label IDs from 1 to the number of classes.
labelIDs = 1 : numClasses;

pxds = pixelLabelDatastore(labelsFolder, classNames, labelIDs);

この例のサポート関数の節で定義されている関数 helperDisplayLidarOverlayImage を使用して、対応する強度イメージに重ね合わせることにより、ラベル付けされたイメージの 1 つを読み込んで表示します。

imageNumber = 225;

% Point cloud (channels 1, 2, and 3 are for location, channel 4 is for intensity).
I = readimage(imds, imageNumber);

labelMap = readimage(pxds, imageNumber);
figure;
helperDisplayLidarOverlayImage(I, labelMap, classNames);
title('Ground Truth');

学習セット、検証セット、およびテスト セットの準備

この例に添付されているサポート関数 helperPartitionLidarData を使用して、データを、それぞれ 970、216、431 のイメージを含む学習セット、検証セット、テスト セットに分割します。

[imdsTrain, imdsVal, imdsTest, pxdsTrain, pxdsVal, pxdsTest] = ...
    helperPartitionLidarData(imds, pxds);

関数combineを使用して、学習データ セットおよび検証データ セットのピクセル データストアとイメージ データストアを結合します。

trainingData = combine(imdsTrain, pxdsTrain); 
validationData = combine(imdsVal, pxdsVal);

データ拡張

データ拡張は、学習中に元のデータをランダムに変換してネットワークの精度を高めるために使用されます。データ拡張を使用すると、ラベル付き学習サンプルの数を実際に増やさずに、学習データをさらに多様化させることができます。

この例のサポート関数の節で定義されている関数 augmentData でカスタム前処理操作を指定して関数transformを使用し、学習データを拡張します。この関数は、球形の 2 次元イメージと関連するラベルを水平方向にランダムに反転します。データ拡張を学習データ セットにのみ適用します。

augmentedTrainingData = transform(trainingData, @(x) augmentData(x));

クラスの重み付けを使用したクラスのバランス調整

データ セット内のクラス ラベルの分布を確認するには、関数countEachLabel (Computer Vision Toolbox)を使用します。

tbl = countEachLabel(pxds);
tbl(:,{'Name','PixelCount','ImagePixelCount'})
ans=3×3 table
         Name         PixelCount    ImagePixelCount
    ______________    __________    _______________

    {'background'}    1.0473e+08      1.0597e+08   
    {'car'       }    9.7839e+05      8.4738e+07   
    {'truck'     }    2.6017e+05      1.9726e+07   

このデータ セットのクラスは不均衡です。これは、路上シーンを含む自動車データ セットに共通する問題です。背景クラスは、自動車やトラックのクラスよりも多くの領域をカバーしています。学習では上位クラスを優先してバイアスがかけられるため、正しく処理されていない場合は、こうした不均衡が学習プロセスに悪影響を及ぼす可能性があります。

これらの重みを使用して、クラスの不均衡を修正します。tbl.PixelCount プロパティのピクセル ラベルのカウントを使用して、中央頻度クラスの重みを計算します。

imageFreq = tbl.PixelCount ./ tbl.ImagePixelCount;
classWeights = median(imageFreq) ./ imageFreq
classWeights = 3×1

    0.0133
    1.1423
    1.0000

ネットワーク アーキテクチャの定義

例に添付されているサポート関数 createPointSeg を使用して、PointSeg ネットワークを作成します。このコードは、ネットワークの学習に使用する層グラフを返します。

inputSize = [64 1024 5];

lgraph = createPointSeg(inputSize, classNames, classWeights);

関数 analyzeNetwork を使用して、ネットワーク アーキテクチャを対話的に可視化して表示します。

analyzeNetwork(lgraph)

学習オプションの指定

rmsprop 最適化アルゴリズムを使用してネットワークに学習させます。関数 trainingOptions を使用して、アルゴリズムのハイパーパラメーターを指定します。

maxEpochs = 30;
initialLearningRate= 5e-4;
miniBatchSize = 8;
l2reg = 2e-4;

options = trainingOptions('rmsprop', ...
    'InitialLearnRate', initialLearningRate, ...
    'L2Regularization', l2reg, ...
    'MaxEpochs', maxEpochs, ...
    'MiniBatchSize', miniBatchSize, ...
    'LearnRateSchedule', 'piecewise', ...
    'LearnRateDropFactor', 0.1, ...
    'LearnRateDropPeriod', 10, ...
    'ValidationData', validationData, ...
    'Plots', 'training-progress', ...
    'VerboseFrequency', 20);

メモ: miniBatchSize を減らして、学習時のメモリ使用量を制御します。

ネットワークの学習

doTrainingtrue の場合は、関数trainNetworkを使用して PointSeg ネットワークに学習させます。そうでない場合は、事前学習済みのネットワークを読み込みます。

ネットワークに学習させるのに CPU または GPU を使用できます。GPU を使用するには、Parallel Computing Toolbox™、および CUDA® 対応の NVIDIA® GPU が必要です。詳細については、GPU 計算の要件 (Parallel Computing Toolbox)を参照してください。

if doTraining    
    [net, info] = trainNetwork(trainingData, lgraph, options);
else
    pretrainedNetwork = load('trainedPointSegNet.mat');
    net = pretrainedNetwork.net;
end

テスト点群での結果の予測

学習済みのネットワークを使用して、テスト点群での結果を予測し、セグメンテーション結果を表示します。

まず、PCD ファイルを読み取り、点群を 5 チャネルの入力イメージに変換します。学習済みのネットワークを使用してラベルを予測します。セグメンテーションを重ね合わせて Figure を表示します。

ptCloud = pcread('ousterLidarDrivingData.pcd');
I = helperPointCloudToImage(ptCloud);
predictedResult = semanticseg(I, net);

figure;
helperDisplayLidarOverlayImage(I, predictedResult, classNames);
title('Semantic Segmentation Result');

この例のサポート関数のセクションで定義されている補助関数 helperDisplayLidarOverlayPointCloud を使用して、3 次元点群オブジェクト ptCloud でのセグメンテーション結果を表示します。

figure;
helperDisplayLidarOverlayPointCloud(ptCloud, predictedResult, numClasses);
view([95.71 24.14])
title('Semantic Segmentation Result on Point Cloud');

ネットワークの評価

テスト セット全体で関数 semanticseg を実行して、ネットワークの精度を測定します。MiniBatchSize の値を 8 に設定して、イメージをセグメント化するときのメモリ使用量を減らします。システムの GPU メモリ量に応じて、この値は増減できます。

outputLocation = fullfile(tempdir, 'output');
if ~exist(outputLocation,'dir')
    mkdir(outputLocation);
end
pxdsResults = semanticseg(imdsTest, net, ...
                'MiniBatchSize', 8, ...
                'WriteLocation', outputLocation, ...
                'Verbose', false);

関数 semanticseg は、テスト データ セットのセグメンテーション結果を PixelLabelDatastore オブジェクトとして返します。この関数は、imdsTest オブジェクト内の各テスト イメージの実際のピクセル ラベル データを、'WriteLocation' 引数で指定されたディスクの場所に書き込みます。

関数evaluateSemanticSegmentation (Computer Vision Toolbox)を使用して、テスト セットの結果からセマンティック セグメンテーション メトリクスを計算します。

metrics = evaluateSemanticSegmentation(pxdsResults, pxdsTest, 'Verbose', false);

Intersection over Union (IoU) メトリクスを使用して、クラスごとのオーバーラップの量を測定できます。

関数 evaluateSemanticSegmentation は、データ セット全体、個々のクラス、および各テスト イメージのメトリクスを返します。データ セット レベルでメトリクスを表示するには、metrics.DataSetMetrics プロパティを使用します。

metrics.DataSetMetrics
ans=1×5 table
    GlobalAccuracy    MeanAccuracy    MeanIoU    WeightedIoU    MeanBFScore
    ______________    ____________    _______    ___________    ___________

       0.99209          0.83752       0.67895      0.98685        0.91654  

データ セット メトリクスは、ネットワーク パフォーマンスの概要を提供します。各クラスが全体的なパフォーマンスに与える影響を確認するには、metrics.ClassMetrics プロパティを使用して各クラスのメトリクスを検査します。

metrics.ClassMetrics
ans=3×3 table
                  Accuracy      IoU      MeanBFScore
                  ________    _______    ___________

    background    0.99466     0.99212      0.98529  
    car           0.75977     0.50096      0.82682  
    truck         0.75814     0.54378      0.77119  

ネットワーク全体のパフォーマンスは良好ですが、クラス メトリクスは、偏りのあるクラス (自動車とトラック) が、データが豊富なクラス (背景) ほどにはセグメント化されていないことを示しています。自動車とトラックのクラスを含むよりラベル付けされたデータでネットワークに学習させることにより、ネットワークのパフォーマンスを改善できます。

サポート関数

データを拡張する関数

関数 augmentData は、2 次元球面イメージと関連するラベルを水平方向にランダムに反転します。

function out = augmentData(inp)
%augmentData Apply random horizontal flipping.

out = cell(size(inp));

% Randomly flip the five-channel image and pixel labels horizontally.
I = inp{1};
sz = size(I);
tform = randomAffine2d('XReflection',true);
rout = affineOutputView(sz,tform,'BoundsStyle','centerOutput');

out{1} = imwarp(I,tform,'OutputView',rout);
out{2} = imwarp(inp{2},tform,'OutputView',rout);
end

2 次元球面イメージに LIDAR セグメンテーション マップを重ねて表示する関数

関数 helperDisplayLidarOverlayImage は、セマンティック セグメンテーション マップを 2 次元球面イメージの強度チャネルに重ね合わせます。この関数は、より見やすくなるように、重ね合わされたイメージのサイズも変更します。

function helperDisplayLidarOverlayImage(lidarImage, labelMap, classNames)
%helperDisplayLidarOverlayImage Overlay labels over the intensity image. 
% 
%  helperDisplayLidarOverlayImage(lidarImage, labelMap, classNames) 
%  displays the overlaid image. lidarImage is a five-channel lidar input. 
%  labelMap contains pixel labels and classNames is an array of label 
%  names.

% Read the intensity channel from the lidar image.
intensityChannel = uint8(lidarImage(:,:,4));

% Load the lidar color map.
cmap = helperLidarColorMap();

% Overlay the labels over the intensity image.
B = labeloverlay(intensityChannel,labelMap,'Colormap',cmap,'Transparency',0.4);

% Resize for better visualization.
B = imresize(B, 'Scale', [3 1], 'method', 'nearest');
imshow(B);

% Display the color bar.
helperPixelLabelColorbar(cmap, classNames); 
end

3 次元点群に LIDAR セグメンテーション マップを重ねて表示する関数

関数 helperDisplayLidarOverPointCloud は、オーガナイズド 3 次元点群にセグメンテーション結果を重ね合わせます。

function helperDisplayLidarOverlayPointCloud(ptCloud, labelMap, numClasses)
%helperDisplayLidarOverlayPointCloud Overlay labels over a point cloud object. 
% 
%  helperDisplayLidarOverlayPointCloud(ptCloud, labelMap, numClasses)
%  displays the overlaid pointCloud object. ptCloud is the organized
%  3-D point cloud input. labelMap contains pixel labels and numClasses
%  is the number of predicted classes.

sz = size(labelMap);

% Apply the color red to cars.
carClassCar = zeros(sz(1), sz(2), numClasses, 'uint8');
carClassCar(:,:,1) = 255*ones(sz(1), sz(2), 'uint8');

% Apply the color blue to trucks.
truckClassColor = zeros(sz(1), sz(2), numClasses, 'uint8');
truckClassColor(:,:,3) = 255*ones(sz(1), sz(2), 'uint8');

% Apply the color gray to the background.
backgroundClassColor = 153*ones(sz(1), sz(2), numClasses, 'uint8');

% Extract indices from the labels.
carIndices = labelMap == 'car';
truckIndices = labelMap == 'truck';
backgroundIndices = labelMap == 'background';

% Extract a point cloud for each class.
carPointCloud = select(ptCloud, carIndices, 'OutputSize','full');
truckPointCloud = select(ptCloud, truckIndices, 'OutputSize','full');
backgroundPointCloud = select(ptCloud, backgroundIndices, 'OutputSize','full');

% Apply colors to different classes.
carPointCloud.Color = carClassCar;
truckPointCloud.Color = truckClassColor;
backgroundPointCloud.Color = backgroundClassColor;

% Merge and add all the processed point clouds with class information.
coloredCloud = pcmerge(carPointCloud, truckPointCloud, 0.01);
coloredCloud = pcmerge(coloredCloud, backgroundPointCloud, 0.01);

% Plot the colored point cloud. Set an ROI for better visualization.
ax = pcshow(coloredCloud);
set(ax,'XLim',[-35.0 35.0],'YLim',[-32.0 32.0],'ZLim',[-3 8], ...
    'XColor','none','YColor','none','ZColor','none');
set(get(ax,'parent'), 'units','normalized');
end

LIDAR カラーマップを定義する関数

関数 helperLidarColorMap は、LIDAR データ セットで使用されるカラーマップを定義します。

function cmap = helperLidarColorMap()

cmap = [
   0.00  0.00   0.00  % background
   0.98  0.00   0.00  % car
   0.00  0.00   0.98  % truck
   ];
end

ピクセル ラベル カラー バーを表示する関数

関数 helperPixelLabelColorbar は、現在の軸にカラー バーを追加します。カラー バーは、クラス名を色で表示するように書式設定されています。

function helperPixelLabelColorbar(cmap, classNames)

colormap(gca, cmap);

% Add a colorbar to the current figure.
c = colorbar('peer', gca);

% Use class names for tick marks.
c.TickLabels = classNames;
numClasses = size(classNames, 1);

% Center tick labels.
c.Ticks = 1/(numClasses * 2):1/numClasses:1;

% Remove tick marks.
c.TickLength = 0;
end

参考文献

[1] Wang, Yuan, Tianyue Shi, Peng Yun, Lei Tai, and Ming Liu. “PointSeg: Real-Time Semantic Segmentation Based on 3D LiDAR Point Cloud.” ArXiv:1807.06288 [Cs], September 25, 2018. http://arxiv.org/abs/1807.06288.