diff --git a/notebooks/3D-point-pillars/.dockerignore b/notebooks/3D-point-pillars/.dockerignore
new file mode 100644
index 00000000000..b476af28dcd
--- /dev/null
+++ b/notebooks/3D-point-pillars/.dockerignore
@@ -0,0 +1,36 @@
+# Git files
+.git
+.gitignore
+.gitattributes
+
+# Python cache
+__pycache__/
+*.py[cod]
+*$py.class
+*.so
+
+# Build artifacts
+build/
+dist/
+*.egg-info/
+.eggs/
+
+# IDE
+.vscode/
+.idea/
+*.swp
+*.swo
+*~
+
+# OS files
+.DS_Store
+Thumbs.db
+
+# Documentation
+*.md
+!README.md
+figures/
+misc/
+
+# Docker files
+devops/
diff --git a/notebooks/3D-point-pillars/.gitignore b/notebooks/3D-point-pillars/.gitignore
new file mode 100644
index 00000000000..fb92f996509
--- /dev/null
+++ b/notebooks/3D-point-pillars/.gitignore
@@ -0,0 +1,8 @@
+__pycache__
+build/
+*.egg-info
+*.so
+*_logs*
+tmp/
+results/
+.idea
diff --git a/notebooks/3D-point-pillars/LICENSE b/notebooks/3D-point-pillars/LICENSE
new file mode 100644
index 00000000000..c49b16c07b3
--- /dev/null
+++ b/notebooks/3D-point-pillars/LICENSE
@@ -0,0 +1,21 @@
+MIT License
+
+Copyright (c) 2023 ZhuLifa
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
diff --git a/notebooks/3D-point-pillars/README.md b/notebooks/3D-point-pillars/README.md
new file mode 100644
index 00000000000..fd55c61203f
--- /dev/null
+++ b/notebooks/3D-point-pillars/README.md
@@ -0,0 +1,153 @@
+# Note
+
+_This directory is a fork from [PointPillars](https://github.com/zhulf0804/PointPillars) (commit 620e6b0)._
+-----------------------
+
+# [PointPillars: Fast Encoders for Object Detection from Point Clouds](https://arxiv.org/abs/1812.05784)
+
+A Simple PointPillars PyTorch Implenmentation for 3D Lidar(KITTI) Detection. [[Zhihu](https://zhuanlan.zhihu.com/p/521277176)]
+
+- It can be run without installing [Spconv](https://github.com/traveller59/spconv), [mmdet](https://github.com/open-mmlab/mmdetection) or [mmdet3d](https://github.com/open-mmlab/mmdetection3d).
+- Only one detection network (PointPillars) was implemented in this repo, so the code may be more easy to read.
+- Sincere thanks for the great open-source architectures [mmcv](https://github.com/open-mmlab/mmcv), [mmdet](https://github.com/open-mmlab/mmdetection) and [mmdet3d](https://github.com/open-mmlab/mmdetection3d), which helps me to learn 3D detetion and implement this repo.
+
+## News
+
+- **2025-02** Making PointPillars a python package out of the code is supported.
+- **2024-04** Exporting PointPillars to ONNX & TensorRT is supported on branch [feature/deployment](https://github.com/zhulf0804/PointPillars/tree/feature/deployment).
+
+ 
+
+## mAP on KITTI validation set (Easy, Moderate, Hard)
+
+| Repo | Metric | Overall | Pedestrian | Cyclist | Car |
+| :---: | :---: | :---: | :---: | :---: | :---: |
+| this repo | 3D-BBox | 73.3259 62.7834 59.6278 | 51.4642 47.9446 43.8040 | 81.8677 63.6617 60.9126 | 86.6456 76.7439 74.1668 |
+| [mmdet3d v0.18.1](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1) | 3D-BBox | 72.0537, 60.1114, 55.8320 | 52.0263, 46.4037, 42.4841 | 78.7231, 59.9526, 57.2489 | 85.4118, 73.9780, 67.7630 |
+| this repo | BEV | 77.8540 69.8003 66.6699 | 59.1687 54.3456 50.5023 | 84.4268 67.1409 63.7409 | 89.9664 87.9145 85.7664 |
+| [mmdet3d v0.18.1](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1) | BEV | 76.6485, 67.7609, 64.5605 | 59.0778, 53.3638, 48.4230 | 80.9328, 63.3447, 60.0618 | 89.9348, 86.5743, 85.1967 |
+| this repo | 2D-BBox | 80.5097 74.6120 71.4758 | 64.6249 61.4201 57.5965 | 86.2569 73.0828 70.1726 | 90.6471 89.3330 86.6583 |
+| [mmdet3d v0.18.1](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1) | 2D-BBox | 78.4938, 73.4781, 70.3613 | 62.2413, 58.9157, 55.3660 | 82.6460, 72.3547, 68.4669 | 90.5939, 89.1638, 87.2511 |
+| this repo | AOS | 74.9647 68.1712 65.2817 | 49.3777 46.7284 43.8352 | 85.0412 69.1024 66.2801 | 90.4752 88.6828 85.7298 |
+| [mmdet3d v0.18.1](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1) | AOS | 72.41, 66.23, 63.55 | 46.00, 43.22, 40.94 | 80.85, 67.20, 63.63 | 90.37, 88.27, 86.07 |
+
+- **Note: Here, we report [mmdet3d v0.18.1](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1) (2022/02/09-2022/03/01) performance based on the officially provided [checkpoint](https://github.com/open-mmlab/mmdetection3d/tree/v0.18.1/configs/pointpillars#kitti). Much improvements were made in the [mmdet3d v1.0.0rc1](https://github.com/open-mmlab/mmdetection3d/tree/v1.0.0rc1)**.
+
+## Detection Visualization
+
+
+
+
+## [Install]
+
+Install PointPillars as a python package and all its dependencies as follows:
+
+```
+cd PointPillars/
+pip install -r requirements.txt
+python setup.py build_ext --inplace
+pip install .
+```
+
+## [Datasets]
+
+1. Download
+
+ Download [point cloud](https://s3.eu-central-1.amazonaws.com/avg-kitti/data_object_velodyne.zip)(29GB), [images](https://s3.eu-central-1.amazonaws.com/avg-kitti/data_object_image_2.zip)(12 GB), [calibration files](https://s3.eu-central-1.amazonaws.com/avg-kitti/data_object_calib.zip)(16 MB)和[labels](https://s3.eu-central-1.amazonaws.com/avg-kitti/data_object_label_2.zip)(5 MB)。Format the datasets as follows:
+ ```
+ kitti
+ |- training
+ |- calib (#7481 .txt)
+ |- image_2 (#7481 .png)
+ |- label_2 (#7481 .txt)
+ |- velodyne (#7481 .bin)
+ |- testing
+ |- calib (#7518 .txt)
+ |- image_2 (#7518 .png)
+ |- velodyne (#7518 .bin)
+ ```
+
+2. Pre-process KITTI datasets First
+
+ ```
+ cd PointPillars/
+ python pre_process_kitti.py --data_root your_path_to_kitti
+ ```
+
+ Now, we have datasets as follows:
+ ```
+ kitti
+ |- training
+ |- calib (#7481 .txt)
+ |- image_2 (#7481 .png)
+ |- label_2 (#7481 .txt)
+ |- velodyne (#7481 .bin)
+ |- velodyne_reduced (#7481 .bin)
+ |- testing
+ |- calib (#7518 .txt)
+ |- image_2 (#7518 .png)
+ |- velodyne (#7518 .bin)
+ |- velodyne_reduced (#7518 .bin)
+ |- kitti_gt_database (# 19700 .bin)
+ |- kitti_infos_train.pkl
+ |- kitti_infos_val.pkl
+ |- kitti_infos_trainval.pkl
+ |- kitti_infos_test.pkl
+ |- kitti_dbinfos_train.pkl
+ ```
+
+## [Training]
+
+```
+cd PointPillars/
+python train.py --data_root your_path_to_kitti
+```
+
+## [Evaluation]
+
+```
+cd PointPillars/
+python evaluate.py --ckpt pretrained/epoch_160.pth --data_root your_path_to_kitti
+```
+
+## [Test]
+
+```
+cd PointPillars/
+
+# 1. infer and visualize point cloud detection
+python test.py --ckpt pretrained/epoch_160.pth --pc_path your_pc_path
+
+# 2. infer and visualize point cloud detection and gound truth.
+python test.py --ckpt pretrained/epoch_160.pth --pc_path your_pc_path --calib_path your_calib_path --gt_path your_gt_path
+
+# 3. infer and visualize point cloud & image detection
+python test.py --ckpt pretrained/epoch_160.pth --pc_path your_pc_path --calib_path your_calib_path --img_path your_img_path
+
+
+e.g.
+a. [infer on val set 000134]
+
+python test.py --ckpt pretrained/epoch_160.pth --pc_path pointpillars/dataset/demo_data/val/000134.bin
+
+or
+
+python test.py --ckpt pretrained/epoch_160.pth --pc_path pointpillars/dataset/demo_data/val/000134.bin \
+ --calib_path pointpillars/dataset/demo_data/val/000134.txt \
+ --img_path pointpillars/dataset/demo_data/val/000134.png \
+ --gt_path pointpillars/dataset/demo_data/val/000134_gt.txt
+
+b. [infer on test set 000002]
+
+python test.py --ckpt pretrained/epoch_160.pth --pc_path pointpillars/dataset/demo_data/test/000002.bin
+
+or
+
+python test.py --ckpt pretrained/epoch_160.pth --pc_path pointpillars/dataset/demo_data/test/000002.bin \
+ --calib_path pointpillars/dataset/demo_data/test/000002.txt \
+ --img_path pointpillars/dataset/demo_data/test/000002.png
+```
+
+## Acknowledements
+
+Thanks for the open source code [mmcv](https://github.com/open-mmlab/mmcv), [mmdet](https://github.com/open-mmlab/mmdetection) and [mmdet3d](https://github.com/open-mmlab/mmdetection3d).
diff --git a/notebooks/3D-point-pillars/benchmark-e2eOV.sh b/notebooks/3D-point-pillars/benchmark-e2eOV.sh
new file mode 100755
index 00000000000..11291f0e8a8
--- /dev/null
+++ b/notebooks/3D-point-pillars/benchmark-e2eOV.sh
@@ -0,0 +1,255 @@
+#!/bin/bash
+# Benchmark OpenVINO PointPillars E2E Pipeline
+# Tests voxelization, neural network, and post-processing individually and combined
+#
+# Prerequisites:
+# - Virtual environment activated (auto-activated if .venv exists)
+# - Extension built against the same OpenVINO version as in venv
+# To rebuild: source .venv/bin/activate && cd ov_extensions && rm -rf build && mkdir build && cd build && cmake .. && make -j$(nproc)
+#
+# Usage:
+# ./benchmark-e2eOV.sh [CONFIG] [DEVICE] [NITER] [NIREQ] [NSTREAMS] [MODE]
+#
+# Arguments:
+# CONFIG - Path to config JSON (default: pretrained/pointpillars_full_config.json)
+# DEVICE - OpenVINO device: CPU, GPU (default: CPU)
+# NITER - Number of iterations (default: 1000)
+# NIREQ - Number of async requests (default: 2)
+# NSTREAMS - Number of inference streams (default: 1)
+# MODE - Benchmark mode: all, voxel, nn, postproc, combined (default: all)
+
+set -e
+
+# Activate virtual environment if it exists
+if [ -f ".venv/bin/activate" ]; then
+ source .venv/bin/activate
+fi
+
+# Default arguments
+CONFIG="${1:-pretrained/pointpillars_full_config.json}"
+DEVICE="${2:-CPU}"
+NITER="${3:-1000}"
+NIREQ="${4:-2}"
+NSTREAMS="${5:-1}"
+MODE="${6:-all}"
+
+# Colors for output
+RED='\033[0;31m'
+GREEN='\033[0;32m'
+YELLOW='\033[1;33m'
+BLUE='\033[0;34m'
+NC='\033[0m' # No Color
+
+echo -e "${BLUE}========================================${NC}"
+echo -e "${BLUE}OpenVINO PointPillars E2E Benchmark${NC}"
+echo -e "${BLUE}========================================${NC}"
+echo ""
+echo -e "Configuration:"
+echo -e " Config: ${CONFIG}"
+echo -e " Device: ${DEVICE}"
+echo -e " Iterations: ${NITER}"
+echo -e " Async Reqs: ${NIREQ}"
+echo -e " Streams: ${NSTREAMS}"
+echo -e " Mode: ${MODE}"
+echo ""
+
+# Check if config exists
+if [ ! -f "$CONFIG" ]; then
+ echo -e "${RED}Error: Config file not found: $CONFIG${NC}"
+ exit 1
+fi
+
+# Extract paths from config JSON using Python
+echo -e "${YELLOW}Parsing configuration...${NC}"
+PARSED=$(python -c "
+import json
+import sys
+with open('$CONFIG', 'r') as f:
+ config = json.load(f)
+print(config['extension_lib'])
+print(config['voxel_model'])
+print(config['nn_model'])
+print(config['postproc_model'])
+")
+
+# Read parsed values into variables
+EXT_LIB=$(echo "$PARSED" | sed -n '1p')
+VOXEL_MODEL=$(echo "$PARSED" | sed -n '2p')
+NN_MODEL=$(echo "$PARSED" | sed -n '3p')
+POSTPROC_MODEL=$(echo "$PARSED" | sed -n '4p')
+
+echo -e " Extension: ${EXT_LIB}"
+echo -e " Voxel Model: ${VOXEL_MODEL}"
+echo -e " NN Model: ${NN_MODEL}"
+echo -e " Postproc: ${POSTPROC_MODEL}"
+echo ""
+
+# Check if files exist
+if [ ! -f "$EXT_LIB" ]; then
+ echo -e "${RED}Error: Extension library not found: $EXT_LIB${NC}"
+ echo -e "${YELLOW}Hint: Build the extension first:${NC}"
+ echo -e " cd ov_extensions && rm -rf build && bash build.sh && cd .."
+ exit 1
+fi
+
+for model in "$VOXEL_MODEL" "$NN_MODEL" "$POSTPROC_MODEL"; do
+ if [ ! -f "$model" ]; then
+ echo -e "${RED}Error: Model not found: $model${NC}"
+ exit 1
+ fi
+ # Create empty .bin file if it doesn't exist (for custom ops with no weights)
+ bin_file="${model%.xml}.bin"
+ if [ ! -f "$bin_file" ]; then
+ echo -e "${YELLOW}Creating empty weight file: $bin_file${NC}"
+ touch "$bin_file"
+ fi
+done
+
+# Create results directory
+RESULTS_DIR="./benchmark_results_$(date +%Y%m%d_%H%M%S)"
+mkdir -p "$RESULTS_DIR"
+echo -e "${GREEN}Results will be saved to: $RESULTS_DIR${NC}"
+echo ""
+
+# Common benchmark_app flags
+# Note: -hint none is required to use fine-tune options like -nstreams, -nireq in OpenVINO 2025.x
+BENCHMARK_FLAGS="-d $DEVICE -niter $NITER -nireq $NIREQ -report_type detailed_counters -report_folder $RESULTS_DIR"
+
+# Function to run benchmark
+run_benchmark() {
+ local name=$1
+ local model=$2
+ local use_extension=$3
+ local shape_override=$4 # Optional: input shape override for dynamic models
+
+ echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+ echo -e "${GREEN}Benchmarking: ${name}${NC}"
+ echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+
+ # Build shape argument if provided
+ local shape_arg=""
+ if [ -n "$shape_override" ]; then
+ shape_arg="-shape $shape_override"
+ fi
+
+ # Run benchmark with both throughput and latency hints
+ # "throughput" "latency"
+ for hint in "none -nstreams $NSTREAMS"; do
+ echo -e "${YELLOW}Running with -hint ${hint}${NC}"
+
+ if [ "$use_extension" = "true" ]; then
+ echo -e "Command: benchmark_app -m $model $BENCHMARK_FLAGS -hint $hint -extensions $EXT_LIB $shape_arg"
+ echo ""
+ benchmark_app -m "$model" $BENCHMARK_FLAGS -hint $hint -extensions "$EXT_LIB" $shape_arg | tee -a "$RESULTS_DIR/${name}_output.txt"
+ else
+ echo -e "Command: benchmark_app -m $model $BENCHMARK_FLAGS -hint $hint $shape_arg"
+ echo ""
+ benchmark_app -m "$model" $BENCHMARK_FLAGS -hint $hint $shape_arg | tee -a "$RESULTS_DIR/${name}_output.txt"
+ fi
+ echo ""
+ done
+
+ echo -e "${GREEN}✓ ${name} benchmark complete${NC}"
+ echo ""
+}
+
+# Run benchmarks based on mode
+case "$MODE" in
+ "voxel")
+ # Voxelization has dynamic input [?,4], use typical point cloud size
+ run_benchmark "voxelization" "$VOXEL_MODEL" "true" "points_input[20000,4]"
+ ;;
+ "nn")
+ # NN has dynamic pillar inputs
+ run_benchmark "neural_network" "$NN_MODEL" "false" "pillars[16000,32,4],coors[16000,4],npoints[16000]"
+ ;;
+ "postproc")
+ # Postprocessing expects 3D inputs: [n_anchors*nclasses, H, W]
+ # For PointPillars: 6 anchors (3 classes * 2 rotations), 3 classes
+ # cls_preds: [6*3, H, W] = [18, 248, 216]
+ # box_preds: [6*7, H, W] = [42, 248, 216]
+ # dir_cls_preds: [6*2, H, W] = [12, 248, 216]
+ # H=248 (y: 79.36/0.16/2), W=216 (x: 69.12/0.16/2)
+ run_benchmark "postprocessing" "$POSTPROC_MODEL" "true" "bbox_cls_pred[18,248,216],bbox_pred[42,248,216],bbox_dir_cls_pred[12,248,216]"
+ ;;
+ "combined")
+ echo -e "${YELLOW}Note: benchmark_app runs models individually.${NC}"
+ echo -e "${YELLOW}For true E2E latency, use profile-e2eOV.py instead.${NC}"
+ echo ""
+ run_benchmark "1_voxelization" "$VOXEL_MODEL" "true" "points_input[20000,4]"
+ run_benchmark "2_neural_network" "$NN_MODEL" "false" "pillars[16000,32,4],coors[16000,4],npoints[16000]"
+ run_benchmark "3_postprocessing" "$POSTPROC_MODEL" "true" "bbox_cls_pred[18,248,216],bbox_pred[42,248,216],bbox_dir_cls_pred[12,248,216]"
+ ;;
+ "all")
+ run_benchmark "1_voxelization" "$VOXEL_MODEL" "true" "points_input[20000,4]"
+ run_benchmark "2_neural_network" "$NN_MODEL" "false" "pillars[16000,32,4],coors[16000,4],npoints[16000]"
+ run_benchmark "3_postprocessing" "$POSTPROC_MODEL" "true" "bbox_cls_pred[18,248,216],bbox_pred[42,248,216],bbox_dir_cls_pred[12,248,216]"
+ ;;
+ *)
+ echo -e "${RED}Error: Unknown mode: $MODE${NC}"
+ echo -e "Valid modes: all, voxel, nn, postproc, combined"
+ exit 1
+ ;;
+esac
+
+# Generate summary report
+echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+echo -e "${GREEN}Benchmark Summary${NC}"
+echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+echo ""
+echo -e "Results saved to: ${RESULTS_DIR}"
+echo ""
+echo -e "Quick summary (extract from outputs):"
+total_median_latency=0
+for output_file in "$RESULTS_DIR"/*_output.txt; do
+ if [ -f "$output_file" ]; then
+ name=$(basename "$output_file" _output.txt)
+ echo -e "${YELLOW}${name}:${NC}"
+
+ # Extract Throughput from last match (final benchmark run)
+ throughput=$(grep "Throughput:" "$output_file" 2>/dev/null | tail -1 | sed 's/.*Throughput:/Throughput:/')
+ if [ -n "$throughput" ]; then
+ echo " $throughput"
+ fi
+
+ # Extract Latency block from last occurrence (final benchmark run)
+ # Get line number of last "Latency:" occurrence and print next 4 lines
+ latency_line=$(grep -n "Latency:" "$output_file" 2>/dev/null | tail -1 | cut -d: -f1)
+ if [ -n "$latency_line" ]; then
+ echo " Latency:"
+ # Extract lines and remove "[ INFO ]" prefix
+ sed -n "$((latency_line+1)),$((latency_line+4))p" "$output_file" | sed 's/\[ INFO \]//g' | sed 's/^/ /'
+
+ # Extract median latency value for E2E calculation
+ median_latency=$(sed -n "$((latency_line+1))p" "$output_file" | grep -oE '[0-9]+\.[0-9]+' | head -1)
+ if [ -n "$median_latency" ]; then
+ total_median_latency=$(python -c "print($total_median_latency + $median_latency)")
+ fi
+ fi
+ echo ""
+ fi
+done
+
+# Calculate and display E2E metrics
+if [ "$MODE" = "all" ] || [ "$MODE" = "combined" ]; then
+ echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+ echo -e "${GREEN}End-to-End Performance (Sum of Median Latencies)${NC}"
+ echo -e "${BLUE}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+ is_valid=$(python -c "print(1 if $total_median_latency > 0 else 0)")
+ if [ "$is_valid" -eq 1 ]; then
+ e2e_fps=$(python -c "print(f'{1000 / $total_median_latency:.2f}')")
+ echo -e " Total Latency: ${GREEN}${total_median_latency} ms${NC}"
+ echo -e " E2E Throughput: ${GREEN}${e2e_fps} FPS${NC}"
+ else
+ echo -e " ${RED}Could not calculate E2E latency${NC}"
+ fi
+ echo ""
+fi
+
+echo -e "${GREEN}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+echo -e "${GREEN}Benchmark Complete!${NC}"
+echo -e "${GREEN}━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━${NC}"
+echo ""
+echo -e "View detailed reports:"
+echo -e " ls -lh $RESULTS_DIR"
+echo ""
diff --git a/notebooks/3D-point-pillars/devops/Dockerfile b/notebooks/3D-point-pillars/devops/Dockerfile
new file mode 100644
index 00000000000..190dd61616b
--- /dev/null
+++ b/notebooks/3D-point-pillars/devops/Dockerfile
@@ -0,0 +1,84 @@
+ARG PYTHON_VERSION=3.10
+ARG UBUNTU_VERSION=24.04
+
+ARG http_proxy
+ARG https_proxy
+ARG no_proxy
+
+FROM ubuntu:${UBUNTU_VERSION} AS base-selected
+
+# Set environment variables
+ENV DEBIAN_FRONTEND=noninteractive
+ENV LANG=C.UTF-8
+ENV LC_ALL=C.UTF-8
+
+# Install system dependencies
+RUN apt update && \
+ apt install -y --no-install-recommends \
+ software-properties-common \
+ cmake \
+ build-essential \
+ libx11-6 \
+ libgl1
+
+# Install Python and pip
+ARG PYTHON_VERSION
+RUN add-apt-repository -y ppa:deadsnakes/ppa
+RUN apt-get update && \
+ apt-get install -y --no-install-recommends \
+ python${PYTHON_VERSION} \
+ python${PYTHON_VERSION}-dev \
+ python${PYTHON_VERSION}-distutils \
+ python3-pip \
+ && rm -rf /var/lib/apt/lists/*
+
+# Create symbolic links for python
+RUN update-alternatives --install /usr/bin/python python /usr/bin/python${PYTHON_VERSION} 1 && \
+ update-alternatives --install /usr/bin/python3 python3 /usr/bin/python${PYTHON_VERSION} 1
+
+# Upgrade pip, setuptools, wheel, blinker
+RUN python -m pip install --no-cache-dir --upgrade --ignore-installed pip setuptools wheel blinker
+
+# intel GPU
+RUN cd /usr/lib/python3/dist-packages/ && \
+ ln -s apt_pkg.cpython-312-x86_64-linux-gnu.so apt_pkg.so
+
+RUN add-apt-repository -y ppa:kobuk-team/intel-graphics || true
+RUN apt update && \
+ apt install -y --no-install-recommends \
+ libze-intel-gpu1 \
+ intel-opencl-icd
+
+
+
+
+# Set working directory
+WORKDIR /workspace
+
+# Install Python packages
+COPY requirements.txt .
+RUN python -m pip install --no-cache-dir -r requirements.txt
+
+# Building torch extensions...
+COPY pointpillars/ ./pointpillars/
+COPY setup.py .
+RUN CPU_BUILD=1 python setup.py build_ext --inplace
+
+# Building OpenVINO extensions...
+COPY ov_extensions ./ov_extensions
+RUN cd ov_extensions && rm -rf build && bash build.sh && cd ..
+
+# Exporting OpenVINO model
+COPY export_ov_e2e.py .
+COPY pretrained ./pretrained
+# python export_ov_e2e.py --checkpoint pretrained/epoch_160.pth --output pretrained/pointpillars_ov
+
+# Test
+COPY e2eOVInference.py .
+COPY test-e2eOV.py .
+# python test-e2eOV.py --device CPU
+# python test-e2eOV.py --device GPU
+
+# Evaluation Kitti
+COPY evaluate-e2eOV.py .
+# python evaluate-e2eOV.py --data_root /Datasets --nsamples 10
diff --git a/notebooks/3D-point-pillars/devops/build.sh b/notebooks/3D-point-pillars/devops/build.sh
new file mode 100755
index 00000000000..76de5ead789
--- /dev/null
+++ b/notebooks/3D-point-pillars/devops/build.sh
@@ -0,0 +1,37 @@
+#!/bin/bash
+# Build script for PointPillars Docker image
+# Usage: ./devops/build.sh
+
+set -e
+
+SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
+PROJECT_ROOT="$(dirname "$SCRIPT_DIR")"
+
+# Color output
+RED='\033[0;31m'
+GREEN='\033[0;32m'
+YELLOW='\033[1;33m'
+BLUE='\033[0;34m'
+NC='\033[0m' # No Color
+
+echo -e "${GREEN}Building PointPillars Docker image${NC}"
+
+echo -e "${YELLOW}Building OpenVino E2E image ...${NC}"
+docker build \
+ --build-arg BUILD_TYPE=e2eOV \
+ --build-arg PYTHON_VERSION=3.10 \
+ --build-arg UBUNTU_VERSION=24.04 \
+ --build-arg http_proxy="${http_proxy}" \
+ --build-arg https_proxy="${https_proxy}" \
+ --build-arg no_proxy="${no_proxy}" \
+ -t pointpillars:e2eOV \
+ -f "${SCRIPT_DIR}/Dockerfile" \
+ "${PROJECT_ROOT}" \
+ "${@:2}"
+if [ $? -eq 0 ]; then
+ echo -e "${GREEN}Successfully built pointpillars:e2eOV${NC}"
+else
+ rc=$?
+ echo -e "${RED}Failed to build pointpillars:e2eOV (exit code: ${rc})${NC}" >&2
+ exit ${rc}
+fi
diff --git a/notebooks/3D-point-pillars/devops/docker-compose.yml b/notebooks/3D-point-pillars/devops/docker-compose.yml
new file mode 100644
index 00000000000..a507288f2a2
--- /dev/null
+++ b/notebooks/3D-point-pillars/devops/docker-compose.yml
@@ -0,0 +1,17 @@
+services:
+ pp-e2eov:
+ image: pointpillars:e2eOV
+ container_name: pointpillars-e2eOV
+ # environment:
+ # - LIBVA_DRIVER_NAME=iHD
+ # devices:
+ # - /dev/dri:/dev/dri
+ # volumes:
+ # - ${DATA_ROOT}:/Datasets:ro
+ working_dir: /workspace
+ command: >
+ bash -c "python export_ov_e2e.py --checkpoint pretrained/epoch_160.pth --output pretrained/pointpillars_ov
+ && python test-e2eOV.py --device CPU"
+ # python test-e2eOV.py --device GPU
+ # python evaluate-e2eOV.py --data_root /Datasets --nsamples 10
+
diff --git a/notebooks/3D-point-pillars/e2eOVInference.py b/notebooks/3D-point-pillars/e2eOVInference.py
new file mode 100644
index 00000000000..ad072e0ea9d
--- /dev/null
+++ b/notebooks/3D-point-pillars/e2eOVInference.py
@@ -0,0 +1,191 @@
+"""
+End-to-End OpenVINO Inference for PointPillars
+Uses custom extensions for voxelization and post-processing
+"""
+
+import json
+import numpy as np
+from openvino import Core, Tensor
+
+
+class E2EOVInference:
+ """
+ End-to-End OpenVINO inference engine for PointPillars
+ Uses custom extensions for voxelization and post-processing
+ """
+
+ def __init__(self, config_path='pretrained/pointpillars_full_config.json', device='CPU'):
+ """
+ Initialize OpenVINO inference engine
+
+ Args:
+ config_path: Path to configuration JSON file
+ device: OpenVINO device ('CPU', 'GPU', etc.)
+ """
+ self.device = device.upper()
+ print(f"Initializing E2E OpenVINO backend on {self.device}...")
+
+ # Load models and extension
+ with open(config_path, 'r') as f:
+ config = json.load(f)
+
+ self.core = Core()
+ self.core.add_extension(config['extension_lib'])
+
+ # Load and compile models
+ voxel_model = self.core.read_model(config['voxel_model'])
+ self.compiled_voxel = self.core.compile_model(voxel_model, 'CPU')
+
+ nn_model = self.core.read_model(config['nn_model'])
+ self.compiled_nn = self.core.compile_model(nn_model, self.device)
+
+ postproc_model = self.core.read_model(config['postproc_model'])
+ self.compiled_postproc = self.core.compile_model(postproc_model, 'CPU')
+
+ print(f"✓ OpenVINO models loaded:")
+ print(" - Voxelization (custom extension) in CPU")
+ print(f" - Neural Network (OpenVINO IR) in {self.device}")
+ print(" - Post-processing (custom extension) in CPU")
+
+ def _voxelize(self, points):
+ """Voxelization using OpenVINO custom extension"""
+ points = np.asarray(points, dtype=np.float32)
+ if points.ndim == 1:
+ points = points.reshape(-1, 4)
+
+ infer_request = self.compiled_voxel.create_infer_request()
+ infer_request.set_input_tensor(0, Tensor(points))
+ infer_request.infer()
+
+ pillars = infer_request.get_output_tensor(0).data
+ coors = infer_request.get_output_tensor(1).data
+ npoints = infer_request.get_output_tensor(2).data
+
+ return pillars, coors, npoints
+
+ def _run_nn(self, pillars, coors, npoints):
+ """Neural network inference"""
+ infer_request = self.compiled_nn.create_infer_request()
+ infer_request.infer({
+ 'pillars': pillars.astype(np.float32),
+ 'coors': coors.astype(np.int32),
+ 'npoints': npoints.astype(np.int32)
+ })
+
+ cls_preds = infer_request.get_output_tensor(0).data
+ box_preds = infer_request.get_output_tensor(1).data
+ dir_cls_preds = infer_request.get_output_tensor(2).data
+
+ return cls_preds, box_preds, dir_cls_preds
+
+ def _postprocess(self, cls_preds, box_preds, dir_cls_preds):
+ """Post-processing using OpenVINO custom extension"""
+ # Remove batch dimension
+ cls_preds = np.squeeze(cls_preds, axis=0)
+ box_preds = np.squeeze(box_preds, axis=0)
+ dir_cls_preds = np.squeeze(dir_cls_preds, axis=0)
+
+ infer_request = self.compiled_postproc.create_infer_request()
+ infer_request.set_input_tensor(0, Tensor(cls_preds))
+ infer_request.set_input_tensor(1, Tensor(box_preds))
+ infer_request.set_input_tensor(2, Tensor(dir_cls_preds))
+ infer_request.infer()
+
+ bboxes = infer_request.get_output_tensor(0).data
+ labels = infer_request.get_output_tensor(1).data
+ scores = infer_request.get_output_tensor(2).data
+
+ return bboxes, labels, scores
+
+ def infer(self, points):
+ """
+ Run inference on point cloud
+
+ Args:
+ points: numpy array of shape [N, 4] (x, y, z, intensity)
+
+ Returns:
+ dict with keys: 'lidar_bboxes', 'labels', 'scores'
+ """
+ # Step 1: Voxelization
+ pillars, coors, npoints = self._voxelize(points)
+
+ # Step 2: Neural network
+ cls_preds, box_preds, dir_cls_preds = self._run_nn(pillars, coors, npoints)
+
+ # Step 3: Post-processing
+ bboxes, labels, scores = self._postprocess(cls_preds, box_preds, dir_cls_preds)
+
+ return {
+ 'lidar_bboxes': bboxes,
+ 'labels': labels,
+ 'scores': scores
+ }
+
+
+if __name__ == "__main__":
+ import argparse
+
+ def point_range_filter(pts, point_range=[0, -39.68, -3, 69.12, 39.68, 1]):
+ """Filter points within specified range"""
+ flag_x_low = pts[:, 0] > point_range[0]
+ flag_y_low = pts[:, 1] > point_range[1]
+ flag_z_low = pts[:, 2] > point_range[2]
+ flag_x_high = pts[:, 0] < point_range[3]
+ flag_y_high = pts[:, 1] < point_range[4]
+ flag_z_high = pts[:, 2] < point_range[5]
+ keep_mask = flag_x_low & flag_y_low & flag_z_low & flag_x_high & flag_y_high & flag_z_high
+ pts = pts[keep_mask]
+ return pts
+
+ def keep_bbox_from_lidar_range(result, pcd_limit_range):
+ """Filter bboxes within specified range"""
+ lidar_bboxes = result['lidar_bboxes']
+ labels = result['labels']
+ scores = result['scores']
+
+ flag1 = lidar_bboxes[:, :3] > pcd_limit_range[:3][None, :]
+ flag2 = lidar_bboxes[:, :3] < pcd_limit_range[3:][None, :]
+ keep_flag = np.all(flag1, axis=-1) & np.all(flag2, axis=-1)
+
+ return {
+ 'lidar_bboxes': lidar_bboxes[keep_flag],
+ 'labels': labels[keep_flag],
+ 'scores': scores[keep_flag]
+ }
+
+ # Parse arguments
+ parser = argparse.ArgumentParser(description='PointPillars E2E OpenVINO Inference')
+ parser.add_argument('--device', default='CPU', choices=['CPU', 'GPU'],
+ help='OpenVINO device')
+ parser.add_argument('--config', default='PointPillars/pretrained/pointpillars_ov_config.json',
+ help='Path to config JSON')
+ parser.add_argument('--pc_path', default='PointPillars/pointpillars/dataset/demo_data/val/000134.bin',
+ help='Path to point cloud file')
+ args = parser.parse_args()
+
+ # Initialize engine
+ engine = E2EOVInference(config_path=args.config, device=args.device)
+
+ # Load and filter point cloud
+ pc = np.fromfile(args.pc_path, dtype=np.float32).reshape(-1, 4)
+ pc = point_range_filter(pc)
+
+ print(f"\n✓ Point cloud loaded: {len(pc)} points (after ROI filtering)")
+
+ # Run inference
+ result = engine.infer(pc)
+
+ # Filter results to valid range
+ pcd_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32)
+ result_filter = keep_bbox_from_lidar_range(result, pcd_limit_range)
+
+ # Print results
+ lidar_bboxes = result_filter['lidar_bboxes']
+ labels = result_filter['labels']
+ scores = result_filter['scores']
+
+ print(f"\nDetection Results:")
+ print(f"Detected {len(lidar_bboxes)} objects:")
+ for i, (bbox, label, score) in enumerate(zip(lidar_bboxes, labels, scores)):
+ print(f" Object {i}: class={label}, score={score:.3f}")
diff --git a/notebooks/3D-point-pillars/evaluate-e2eOV.py b/notebooks/3D-point-pillars/evaluate-e2eOV.py
new file mode 100644
index 00000000000..5ffb478a661
--- /dev/null
+++ b/notebooks/3D-point-pillars/evaluate-e2eOV.py
@@ -0,0 +1,430 @@
+"""
+Evaluate PointPillars using E2E OpenVINO inference
+Adapted from evaluate.py
+"""
+
+import argparse
+import numpy as np
+import os
+from tqdm import tqdm
+
+import sys
+REPO_ROOT = os.path.dirname(os.path.abspath(__file__))
+if REPO_ROOT not in sys.path:
+ sys.path.insert(0, REPO_ROOT)
+from pointpillars.utils import keep_bbox_from_image_range, \
+ keep_bbox_from_lidar_range, write_pickle, write_label, \
+ iou2d, iou3d_camera, iou_bev
+from pointpillars.dataset import Kitti, get_dataloader
+
+from e2eOVInference import E2EOVInference
+
+
+def get_score_thresholds(tp_scores, total_num_valid_gt, num_sample_pts=41):
+ """Calculate score thresholds for PR curve"""
+ score_thresholds = []
+ tp_scores = sorted(tp_scores)[::-1]
+ cur_recall, pts_ind = 0, 0
+ for i, score in enumerate(tp_scores):
+ lrecall = (i + 1) / total_num_valid_gt
+ rrecall = (i + 2) / total_num_valid_gt
+
+ if i == len(tp_scores) - 1:
+ score_thresholds.append(score)
+ break
+
+ if (lrecall + rrecall) / 2 < cur_recall:
+ continue
+
+ score_thresholds.append(score)
+ pts_ind += 1
+ cur_recall = pts_ind / (num_sample_pts - 1)
+ return score_thresholds
+
+
+def do_eval(det_results, gt_results, CLASSES, saved_path):
+ """Evaluate detection results against ground truth"""
+
+ # Import torch only for metric computation
+ import torch
+
+ # Device for metric computation
+ device = torch.device('cpu')
+
+ assert len(det_results) == len(gt_results)
+ f = open(os.path.join(saved_path, 'eval_results.txt'), 'w')
+
+ # 1. calculate iou
+ ious = {
+ 'bbox_2d': [],
+ 'bbox_bev': [],
+ 'bbox_3d': []
+ }
+ ids = list(sorted(gt_results.keys()))
+ for id in ids:
+ gt_result = gt_results[id]['annos']
+ det_result = det_results[id]
+
+ # 1.1, 2d bboxes iou
+ gt_bboxes2d = gt_result['bbox'].astype(np.float32)
+ det_bboxes2d = det_result['bbox'].astype(np.float32)
+ gt_bboxes2d_t = torch.from_numpy(gt_bboxes2d).to(device)
+ det_bboxes2d_t = torch.from_numpy(det_bboxes2d).to(device)
+ iou2d_v = iou2d(gt_bboxes2d_t, det_bboxes2d_t)
+ ious['bbox_2d'].append(iou2d_v.cpu().numpy())
+
+ # 1.2, bev iou
+ gt_location = gt_result['location'].astype(np.float32)
+ gt_dimensions = gt_result['dimensions'].astype(np.float32)
+ gt_rotation_y = gt_result['rotation_y'].astype(np.float32)
+ det_location = det_result['location'].astype(np.float32)
+ det_dimensions = det_result['dimensions'].astype(np.float32)
+ det_rotation_y = det_result['rotation_y'].astype(np.float32)
+
+ gt_bev = np.concatenate([gt_location[:, [0, 2]], gt_dimensions[:, [0, 2]], gt_rotation_y[:, None]], axis=-1)
+ det_bev = np.concatenate([det_location[:, [0, 2]], det_dimensions[:, [0, 2]], det_rotation_y[:, None]], axis=-1)
+ gt_bev_t = torch.from_numpy(gt_bev).to(device)
+ det_bev_t = torch.from_numpy(det_bev).to(device)
+ iou_bev_v = iou_bev(gt_bev_t, det_bev_t)
+ ious['bbox_bev'].append(iou_bev_v.cpu().numpy())
+
+ # 1.3, 3dbboxes iou
+ gt_bboxes3d = np.concatenate([gt_location, gt_dimensions, gt_rotation_y[:, None]], axis=-1)
+ det_bboxes3d = np.concatenate([det_location, det_dimensions, det_rotation_y[:, None]], axis=-1)
+ gt_bboxes3d_t = torch.from_numpy(gt_bboxes3d).to(device)
+ det_bboxes3d_t = torch.from_numpy(det_bboxes3d).to(device)
+ iou3d_v = iou3d_camera(gt_bboxes3d_t, det_bboxes3d_t)
+ ious['bbox_3d'].append(iou3d_v.cpu().numpy())
+
+ MIN_IOUS = {
+ 'Pedestrian': [0.5, 0.5, 0.5],
+ 'Cyclist': [0.5, 0.5, 0.5],
+ 'Car': [0.7, 0.7, 0.7]
+ }
+ MIN_HEIGHT = [40, 25, 25]
+
+ overall_results = {}
+ for e_ind, eval_type in enumerate(['bbox_2d', 'bbox_bev', 'bbox_3d']):
+ eval_ious = ious[eval_type]
+ eval_ap_results, eval_aos_results = {}, {}
+ for cls in CLASSES:
+ eval_ap_results[cls] = []
+ eval_aos_results[cls] = []
+ CLS_MIN_IOU = MIN_IOUS[cls][e_ind]
+ for difficulty in [0, 1, 2]:
+ # Calculate metrics (simplified version - core logic same as evaluate-multibackend.py)
+ total_gt_ignores, total_det_ignores, total_dc_bboxes, total_scores = [], [], [], []
+ total_gt_alpha, total_det_alpha = [], []
+
+ for id in ids:
+ gt_result = gt_results[id]['annos']
+ det_result = det_results[id]
+
+ # GT bbox property
+ cur_gt_names = gt_result['name']
+ cur_difficulty = gt_result['difficulty']
+ gt_ignores, dc_bboxes = [], []
+ for j, cur_gt_name in enumerate(cur_gt_names):
+ ignore = cur_difficulty[j] < 0 or cur_difficulty[j] > difficulty
+ if cur_gt_name == cls:
+ valid_class = 1
+ elif cls == 'Pedestrian' and cur_gt_name == 'Person_sitting':
+ valid_class = 0
+ elif cls == 'Car' and cur_gt_name == 'Van':
+ valid_class = 0
+ else:
+ valid_class = -1
+
+ if valid_class == 1 and not ignore:
+ gt_ignores.append(0)
+ elif valid_class == 0 or (valid_class == 1 and ignore):
+ gt_ignores.append(1)
+ else:
+ gt_ignores.append(-1)
+
+ if cur_gt_name == 'DontCare':
+ dc_bboxes.append(gt_result['bbox'][j])
+ total_gt_ignores.append(gt_ignores)
+ total_dc_bboxes.append(np.array(dc_bboxes))
+ total_gt_alpha.append(gt_result['alpha'])
+
+ # Det bbox property
+ cur_det_names = det_result['name']
+ cur_det_heights = det_result['bbox'][:, 3] - det_result['bbox'][:, 1]
+ det_ignores = []
+ for j, cur_det_name in enumerate(cur_det_names):
+ if cur_det_heights[j] < MIN_HEIGHT[difficulty]:
+ det_ignores.append(1)
+ elif cur_det_name == cls:
+ det_ignores.append(0)
+ else:
+ det_ignores.append(-1)
+ total_det_ignores.append(det_ignores)
+ total_scores.append(det_result['score'])
+ total_det_alpha.append(det_result['alpha'])
+
+ # Calculate TP scores
+ tp_scores = []
+ for i, id in enumerate(ids):
+ cur_eval_ious = eval_ious[i]
+ gt_ignores, det_ignores = total_gt_ignores[i], total_det_ignores[i]
+ scores = total_scores[i]
+
+ nn, mm = cur_eval_ious.shape
+ assigned = np.zeros((mm, ), dtype=np.bool_)
+ for j in range(nn):
+ if gt_ignores[j] == -1:
+ continue
+ match_id, match_score = -1, -1
+ for k in range(mm):
+ if not assigned[k] and det_ignores[k] >= 0 and cur_eval_ious[j, k] > CLS_MIN_IOU and scores[k] > match_score:
+ match_id = k
+ match_score = scores[k]
+ if match_id != -1:
+ assigned[match_id] = True
+ if det_ignores[match_id] == 0 and gt_ignores[j] == 0:
+ tp_scores.append(match_score)
+
+ total_num_valid_gt = np.sum([np.sum(np.array(gt_ignores) == 0) for gt_ignores in total_gt_ignores])
+ score_thresholds = get_score_thresholds(tp_scores, total_num_valid_gt)
+
+ # Calculate precision and recall
+ tps, fns, fps, total_aos = [], [], [], []
+ for score_threshold in score_thresholds:
+ tp, fn, fp, aos = 0, 0, 0, 0
+ for i, id in enumerate(ids):
+ cur_eval_ious = eval_ious[i]
+ gt_ignores, det_ignores = total_gt_ignores[i], total_det_ignores[i]
+ gt_alpha, det_alpha = total_gt_alpha[i], total_det_alpha[i]
+ scores = total_scores[i]
+
+ nn, mm = cur_eval_ious.shape
+ assigned = np.zeros((mm, ), dtype=np.bool_)
+ for j in range(nn):
+ if gt_ignores[j] == -1:
+ continue
+ match_id, match_iou = -1, -1
+ for k in range(mm):
+ if not assigned[k] and det_ignores[k] >= 0 and scores[k] >= score_threshold and cur_eval_ious[j, k] > CLS_MIN_IOU:
+ if cur_eval_ious[j, k] > match_iou:
+ match_id = k
+ match_iou = cur_eval_ious[j, k]
+
+ if match_id != -1:
+ assigned[match_id] = True
+ if det_ignores[match_id] == 0 and gt_ignores[j] == 0:
+ tp += 1
+ if eval_type == 'bbox_2d':
+ aos += (1 + np.cos(gt_alpha[j] - det_alpha[match_id])) / 2
+ else:
+ if gt_ignores[j] == 0:
+ fn += 1
+
+ for k in range(mm):
+ if det_ignores[k] == 0 and scores[k] >= score_threshold and not assigned[k]:
+ fp += 1
+
+ # Handle DontCare bboxes for 2D evaluation
+ if eval_type == 'bbox_2d':
+ dc_bboxes = total_dc_bboxes[i]
+ det_bboxes = det_results[id]['bbox']
+ if len(dc_bboxes) > 0:
+ ious_dc = iou2d(torch.from_numpy(det_bboxes).to(device),
+ torch.from_numpy(dc_bboxes).to(device)).cpu().numpy()
+ for k in range(mm):
+ if det_ignores[k] == 0 and scores[k] >= score_threshold and not assigned[k]:
+ if ious_dc[k].max() > CLS_MIN_IOU:
+ fp -= 1
+
+ tps.append(tp)
+ fns.append(fn)
+ fps.append(fp)
+ if eval_type == 'bbox_2d':
+ total_aos.append(aos)
+
+ tps, fns, fps = np.array(tps), np.array(fns), np.array(fps)
+
+ recalls = tps / (tps + fns)
+ precisions = tps / (tps + fps)
+ for i in range(len(score_thresholds)):
+ precisions[i] = np.max(precisions[i:])
+
+ sums_AP = 0
+ for i in range(0, len(score_thresholds), 4):
+ sums_AP += precisions[i]
+ mAP = sums_AP / 11 * 100
+ eval_ap_results[cls].append(mAP)
+
+ if eval_type == 'bbox_2d':
+ total_aos = np.array(total_aos)
+ similarity = total_aos / (tps + fps)
+ for i in range(len(score_thresholds)):
+ similarity[i] = np.max(similarity[i:])
+ sums_similarity = 0
+ for i in range(0, len(score_thresholds), 4):
+ sums_similarity += similarity[i]
+ mSimilarity = sums_similarity / 11 * 100
+ eval_aos_results[cls].append(mSimilarity)
+
+ print(f'=========={eval_type.upper()}==========')
+ print(f'=========={eval_type.upper()}==========', file=f)
+ for k, v in eval_ap_results.items():
+ print(f'{k} AP@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AP@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+ if eval_type == 'bbox_2d':
+ print(f'==========AOS==========')
+ print(f'==========AOS==========', file=f)
+ for k, v in eval_aos_results.items():
+ print(f'{k} AOS@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AOS@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+
+ overall_results[eval_type] = np.mean(list(eval_ap_results.values()), 0)
+ if eval_type == 'bbox_2d':
+ overall_results['AOS'] = np.mean(list(eval_aos_results.values()), 0)
+
+ print(f'\n==========Overall==========')
+ print(f'\n==========Overall==========', file=f)
+ for k, v in overall_results.items():
+ print(f'{k} AP: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AP: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+ f.close()
+
+
+def main(args):
+ """Main evaluation function"""
+ # Allow selecting which point file extension / folder to use via CLI
+ val_dataset = Kitti(data_root=args.data_root,
+ split=args.split,
+ pts_prefix=args.pts_prefix,
+ max_samples=args.nsamples if args.nsamples > 0 else None)
+
+ # If requested, switch dataset to use .pcd files instead of .bin. This assumes
+ # corresponding PCD files exist under a sibling folder (e.g. velodyne_reduced_pcd).
+ if args.use_pcd:
+ # adjust pts_prefix to point to pcd sibling folder
+ val_dataset.pts_prefix = args.pts_prefix + '_pcd'
+ # update stored velodyne_path entries to refer to .pcd extension
+ for k, info in val_dataset.data_infos.items():
+ vp = info.get('velodyne_path')
+ if vp and vp.endswith('.bin'):
+ info['velodyne_path'] = vp[:-4] + '.pcd'
+
+ val_dataloader = get_dataloader(dataset=val_dataset,
+ batch_size=args.batch_size,
+ num_workers=args.num_workers,
+ shuffle=False)
+ CLASSES = Kitti.CLASSES
+ LABEL2CLASSES = {v: k for k, v in CLASSES.items()}
+
+ # Initialize E2E OpenVINO inference engine
+ print("Initializing E2E OpenVINO inference engine...")
+ inference_engine = E2EOVInference(
+ config_path=args.config,
+ device=args.device.upper()
+ )
+
+ saved_path = args.saved_path
+ os.makedirs(saved_path, exist_ok=True)
+ saved_submit_path = os.path.join(saved_path, 'submit')
+ os.makedirs(saved_submit_path, exist_ok=True)
+
+ pcd_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32)
+
+ format_results = {}
+ print('Predicting the results.')
+ for i, data_dict in enumerate(tqdm(val_dataloader)):
+ batched_pts = data_dict['batched_pts']
+
+ # Process each sample in batch
+ batch_results = []
+ for j, pts in enumerate(batched_pts):
+ # Run inference
+ res = inference_engine.infer(pts)
+ batch_results.append(res)
+
+ # Format results
+ for j, result in enumerate(batch_results):
+ format_result = {
+ 'name': [],
+ 'truncated': [],
+ 'occluded': [],
+ 'alpha': [],
+ 'bbox': [],
+ 'dimensions': [],
+ 'location': [],
+ 'rotation_y': [],
+ 'score': []
+ }
+
+ calib_info = data_dict['batched_calib_info'][j]
+ tr_velo_to_cam = calib_info['Tr_velo_to_cam'].astype(np.float32)
+ r0_rect = calib_info['R0_rect'].astype(np.float32)
+ P2 = calib_info['P2'].astype(np.float32)
+ image_shape = data_dict['batched_img_info'][j]['image_shape']
+ idx = data_dict['batched_img_info'][j]['image_idx']
+
+ result_filter = keep_bbox_from_image_range(result, tr_velo_to_cam, r0_rect, P2, image_shape)
+ result_filter = keep_bbox_from_lidar_range(result_filter, pcd_limit_range)
+
+ lidar_bboxes = result_filter['lidar_bboxes']
+ labels, scores = result_filter['labels'], result_filter['scores']
+ bboxes2d, camera_bboxes = result_filter['bboxes2d'], result_filter['camera_bboxes']
+
+ for lidar_bbox, label, score, bbox2d, camera_bbox in \
+ zip(lidar_bboxes, labels, scores, bboxes2d, camera_bboxes):
+ format_result['name'].append(LABEL2CLASSES[label])
+ format_result['truncated'].append(0.0)
+ format_result['occluded'].append(0)
+ alpha = camera_bbox[6] - np.arctan2(camera_bbox[0], camera_bbox[2])
+ format_result['alpha'].append(alpha)
+ format_result['bbox'].append(bbox2d)
+ format_result['dimensions'].append(camera_bbox[3:6])
+ format_result['location'].append(camera_bbox[:3])
+ format_result['rotation_y'].append(camera_bbox[6])
+ format_result['score'].append(score)
+
+ write_label(format_result, os.path.join(saved_submit_path, f'{idx:06d}.txt'))
+ format_results[idx] = {k: np.array(v) for k, v in format_result.items()}
+
+ write_pickle(format_results, os.path.join(saved_path, 'results.pkl'))
+
+ print('Evaluating.. Please wait several seconds.')
+ do_eval(format_results, val_dataset.data_infos, CLASSES, saved_path)
+
+
+if __name__ == '__main__':
+ current_file_path = os.path.dirname(os.path.abspath(__file__))
+ parser = argparse.ArgumentParser(description='E2E OpenVINO PointPillars Evaluation',
+ formatter_class=argparse.ArgumentDefaultsHelpFormatter)
+ parser.add_argument('--data_root', default=f'{current_file_path}/Datasets',
+ help='Data root for KITTI dataset')
+ parser.add_argument('--config', default=f'{current_file_path}/pretrained/pointpillars_ov_config.json',
+ help='Path to OpenVINO config JSON')
+ parser.add_argument('--saved_path', default=f'{current_file_path}/Datasets/results_e2e_ov',
+ help='Path to save evaluation results')
+ parser.add_argument('--batch_size', type=int, default=1,
+ help='Batch size for evaluation')
+ parser.add_argument('--num_workers', type=int, default=4,
+ help='Number of dataloader workers')
+ parser.add_argument('--nsamples', type=int, default=0,
+ help='Number of samples to evaluate (0 for all)')
+ parser.add_argument('--device', default='CPU', choices=['CPU', 'GPU'],
+ help='OpenVINO device')
+ parser.add_argument('--pts-prefix', default='velodyne_reduced',
+ help='Pointcloud folder prefix to use (mirrors Kitti default)')
+ parser.add_argument('--use-pcd', action='store_true',
+ help='Load .pcd files instead of .bin (expects xxx_pcd sibling folder)')
+ parser.add_argument('--split', default='val', choices=['train', 'val', 'trainval', 'test'],
+ help='Which KITTI split to evaluate')
+
+ args = parser.parse_args()
+
+ print("\n" + "="*60)
+ print("E2E OpenVINO PointPillars Evaluation")
+ print("="*60)
+ print("\nConfiguration:")
+ for k, v in vars(args).items():
+ print(f" {k}: {v}")
+ print("="*60 + "\n")
+
+ main(args)
diff --git a/notebooks/3D-point-pillars/evaluate.py b/notebooks/3D-point-pillars/evaluate.py
new file mode 100644
index 00000000000..7e105f7b22e
--- /dev/null
+++ b/notebooks/3D-point-pillars/evaluate.py
@@ -0,0 +1,386 @@
+import argparse
+import numpy as np
+import os
+import torch
+import pdb
+from tqdm import tqdm
+
+from pointpillars.utils import setup_seed, keep_bbox_from_image_range, \
+ keep_bbox_from_lidar_range, write_pickle, write_label, \
+ iou2d, iou3d_camera, iou_bev
+from pointpillars.dataset import Kitti, get_dataloader
+from pointpillars.model import PointPillars
+
+
+def get_score_thresholds(tp_scores, total_num_valid_gt, num_sample_pts=41):
+ score_thresholds = []
+ tp_scores = sorted(tp_scores)[::-1]
+ cur_recall, pts_ind = 0, 0
+ for i, score in enumerate(tp_scores):
+ lrecall = (i + 1) / total_num_valid_gt
+ rrecall = (i + 2) / total_num_valid_gt
+
+ if i == len(tp_scores) - 1:
+ score_thresholds.append(score)
+ break
+
+ if (lrecall + rrecall) / 2 < cur_recall:
+ continue
+
+ score_thresholds.append(score)
+ pts_ind += 1
+ cur_recall = pts_ind / (num_sample_pts - 1)
+ return score_thresholds
+
+
+def do_eval(det_results, gt_results, CLASSES, saved_path):
+ '''
+ det_results: list,
+ gt_results: dict(id -> det_results)
+ CLASSES: dict
+ '''
+ assert len(det_results) == len(gt_results)
+ f = open(os.path.join(saved_path, 'eval_results.txt'), 'w')
+
+ # 1. calculate iou
+ ious = {
+ 'bbox_2d': [],
+ 'bbox_bev': [],
+ 'bbox_3d': []
+ }
+ ids = list(sorted(gt_results.keys()))
+ for id in ids:
+ gt_result = gt_results[id]['annos']
+ det_result = det_results[id]
+
+ # 1.1, 2d bboxes iou
+ gt_bboxes2d = gt_result['bbox'].astype(np.float32)
+ det_bboxes2d = det_result['bbox'].astype(np.float32)
+ iou2d_v = iou2d(torch.from_numpy(gt_bboxes2d).cuda(), torch.from_numpy(det_bboxes2d).cuda())
+ ious['bbox_2d'].append(iou2d_v.cpu().numpy())
+
+ # 1.2, bev iou
+ gt_location = gt_result['location'].astype(np.float32)
+ gt_dimensions = gt_result['dimensions'].astype(np.float32)
+ gt_rotation_y = gt_result['rotation_y'].astype(np.float32)
+ det_location = det_result['location'].astype(np.float32)
+ det_dimensions = det_result['dimensions'].astype(np.float32)
+ det_rotation_y = det_result['rotation_y'].astype(np.float32)
+
+ gt_bev = np.concatenate([gt_location[:, [0, 2]], gt_dimensions[:, [0, 2]], gt_rotation_y[:, None]], axis=-1)
+ det_bev = np.concatenate([det_location[:, [0, 2]], det_dimensions[:, [0, 2]], det_rotation_y[:, None]], axis=-1)
+ iou_bev_v = iou_bev(torch.from_numpy(gt_bev).cuda(), torch.from_numpy(det_bev).cuda())
+ ious['bbox_bev'].append(iou_bev_v.cpu().numpy())
+
+ # 1.3, 3dbboxes iou
+ gt_bboxes3d = np.concatenate([gt_location, gt_dimensions, gt_rotation_y[:, None]], axis=-1)
+ det_bboxes3d = np.concatenate([det_location, det_dimensions, det_rotation_y[:, None]], axis=-1)
+ iou3d_v = iou3d_camera(torch.from_numpy(gt_bboxes3d).cuda(), torch.from_numpy(det_bboxes3d).cuda())
+ ious['bbox_3d'].append(iou3d_v.cpu().numpy())
+
+ MIN_IOUS = {
+ 'Pedestrian': [0.5, 0.5, 0.5],
+ 'Cyclist': [0.5, 0.5, 0.5],
+ 'Car': [0.7, 0.7, 0.7]
+ }
+ MIN_HEIGHT = [40, 25, 25]
+
+ overall_results = {}
+ for e_ind, eval_type in enumerate(['bbox_2d', 'bbox_bev', 'bbox_3d']):
+ eval_ious = ious[eval_type]
+ eval_ap_results, eval_aos_results = {}, {}
+ for cls in CLASSES:
+ eval_ap_results[cls] = []
+ eval_aos_results[cls] = []
+ CLS_MIN_IOU = MIN_IOUS[cls][e_ind]
+ for difficulty in [0, 1, 2]:
+ # 1. bbox property
+ total_gt_ignores, total_det_ignores, total_dc_bboxes, total_scores = [], [], [], []
+ total_gt_alpha, total_det_alpha = [], []
+ for id in ids:
+ gt_result = gt_results[id]['annos']
+ det_result = det_results[id]
+
+ # 1.1 gt bbox property
+ cur_gt_names = gt_result['name']
+ cur_difficulty = gt_result['difficulty']
+ gt_ignores, dc_bboxes = [], []
+ for j, cur_gt_name in enumerate(cur_gt_names):
+ ignore = cur_difficulty[j] < 0 or cur_difficulty[j] > difficulty
+ if cur_gt_name == cls:
+ valid_class = 1
+ elif cls == 'Pedestrian' and cur_gt_name == 'Person_sitting':
+ valid_class = 0
+ elif cls == 'Car' and cur_gt_name == 'Van':
+ valid_class = 0
+ else:
+ valid_class = -1
+
+ if valid_class == 1 and not ignore:
+ gt_ignores.append(0)
+ elif valid_class == 0 or (valid_class == 1 and ignore):
+ gt_ignores.append(1)
+ else:
+ gt_ignores.append(-1)
+
+ if cur_gt_name == 'DontCare':
+ dc_bboxes.append(gt_result['bbox'][j])
+ total_gt_ignores.append(gt_ignores)
+ total_dc_bboxes.append(np.array(dc_bboxes))
+ total_gt_alpha.append(gt_result['alpha'])
+
+ # 1.2 det bbox property
+ cur_det_names = det_result['name']
+ cur_det_heights = det_result['bbox'][:, 3] - det_result['bbox'][:, 1]
+ det_ignores = []
+ for j, cur_det_name in enumerate(cur_det_names):
+ if cur_det_heights[j] < MIN_HEIGHT[difficulty]:
+ det_ignores.append(1)
+ elif cur_det_name == cls:
+ det_ignores.append(0)
+ else:
+ det_ignores.append(-1)
+ total_det_ignores.append(det_ignores)
+ total_scores.append(det_result['score'])
+ total_det_alpha.append(det_result['alpha'])
+
+ # 2. calculate scores thresholds for PR curve
+ tp_scores = []
+ for i, id in enumerate(ids):
+ cur_eval_ious = eval_ious[i]
+ gt_ignores, det_ignores = total_gt_ignores[i], total_det_ignores[i]
+ scores = total_scores[i]
+
+ nn, mm = cur_eval_ious.shape
+ assigned = np.zeros((mm, ), dtype=np.bool_)
+ for j in range(nn):
+ if gt_ignores[j] == -1:
+ continue
+ match_id, match_score = -1, -1
+ for k in range(mm):
+ if not assigned[k] and det_ignores[k] >= 0 and cur_eval_ious[j, k] > CLS_MIN_IOU and scores[k] > match_score:
+ match_id = k
+ match_score = scores[k]
+ if match_id != -1:
+ assigned[match_id] = True
+ if det_ignores[match_id] == 0 and gt_ignores[j] == 0:
+ tp_scores.append(match_score)
+ total_num_valid_gt = np.sum([np.sum(np.array(gt_ignores) == 0) for gt_ignores in total_gt_ignores])
+ score_thresholds = get_score_thresholds(tp_scores, total_num_valid_gt)
+
+ # 3. draw PR curve and calculate mAP
+ tps, fns, fps, total_aos = [], [], [], []
+
+ for score_threshold in score_thresholds:
+ tp, fn, fp = 0, 0, 0
+ aos = 0
+ for i, id in enumerate(ids):
+ cur_eval_ious = eval_ious[i]
+ gt_ignores, det_ignores = total_gt_ignores[i], total_det_ignores[i]
+ gt_alpha, det_alpha = total_gt_alpha[i], total_det_alpha[i]
+ scores = total_scores[i]
+
+ nn, mm = cur_eval_ious.shape
+ assigned = np.zeros((mm, ), dtype=np.bool_)
+ for j in range(nn):
+ if gt_ignores[j] == -1:
+ continue
+ match_id, match_iou = -1, -1
+ for k in range(mm):
+ if not assigned[k] and det_ignores[k] >= 0 and scores[k] >= score_threshold and cur_eval_ious[j, k] > CLS_MIN_IOU:
+
+ if det_ignores[k] == 0 and cur_eval_ious[j, k] > match_iou:
+ match_iou = cur_eval_ious[j, k]
+ match_id = k
+ elif det_ignores[k] == 1 and match_iou == -1:
+ match_id = k
+
+ if match_id != -1:
+ assigned[match_id] = True
+ if det_ignores[match_id] == 0 and gt_ignores[j] == 0:
+ tp += 1
+ if eval_type == 'bbox_2d':
+ aos += (1 + np.cos(gt_alpha[j] - det_alpha[match_id])) / 2
+ else:
+ if gt_ignores[j] == 0:
+ fn += 1
+
+ for k in range(mm):
+ if det_ignores[k] == 0 and scores[k] >= score_threshold and not assigned[k]:
+ fp += 1
+
+ # In case 2d bbox evaluation, we should consider dontcare bboxes
+ if eval_type == 'bbox_2d':
+ dc_bboxes = total_dc_bboxes[i]
+ det_bboxes = det_results[id]['bbox']
+ if len(dc_bboxes) > 0:
+ ious_dc_det = iou2d(torch.from_numpy(det_bboxes), torch.from_numpy(dc_bboxes), metric=1).numpy().T
+ for j in range(len(dc_bboxes)):
+ for k in range(len(det_bboxes)):
+ if det_ignores[k] == 0 and scores[k] >= score_threshold and not assigned[k]:
+ if ious_dc_det[j, k] > CLS_MIN_IOU:
+ fp -= 1
+ assigned[k] = True
+
+ tps.append(tp)
+ fns.append(fn)
+ fps.append(fp)
+ if eval_type == 'bbox_2d':
+ total_aos.append(aos)
+
+ tps, fns, fps = np.array(tps), np.array(fns), np.array(fps)
+
+ recalls = tps / (tps + fns)
+ precisions = tps / (tps + fps)
+ for i in range(len(score_thresholds)):
+ precisions[i] = np.max(precisions[i:])
+
+ sums_AP = 0
+ for i in range(0, len(score_thresholds), 4):
+ sums_AP += precisions[i]
+ mAP = sums_AP / 11 * 100
+ eval_ap_results[cls].append(mAP)
+
+ if eval_type == 'bbox_2d':
+ total_aos = np.array(total_aos)
+ similarity = total_aos / (tps + fps)
+ for i in range(len(score_thresholds)):
+ similarity[i] = np.max(similarity[i:])
+ sums_similarity = 0
+ for i in range(0, len(score_thresholds), 4):
+ sums_similarity += similarity[i]
+ mSimilarity = sums_similarity / 11 * 100
+ eval_aos_results[cls].append(mSimilarity)
+
+ print(f'=========={eval_type.upper()}==========')
+ print(f'=========={eval_type.upper()}==========', file=f)
+ for k, v in eval_ap_results.items():
+ print(f'{k} AP@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AP@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+ if eval_type == 'bbox_2d':
+ print(f'==========AOS==========')
+ print(f'==========AOS==========', file=f)
+ for k, v in eval_aos_results.items():
+ print(f'{k} AOS@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AOS@{MIN_IOUS[k][e_ind]}: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+
+ overall_results[eval_type] = np.mean(list(eval_ap_results.values()), 0)
+ if eval_type == 'bbox_2d':
+ overall_results['AOS'] = np.mean(list(eval_aos_results.values()), 0)
+
+ print(f'\n==========Overall==========')
+ print(f'\n==========Overall==========', file=f)
+ for k, v in overall_results.items():
+ print(f'{k} AP: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}')
+ print(f'{k} AP: {v[0]:.4f} {v[1]:.4f} {v[2]:.4f}', file=f)
+ f.close()
+
+
+def main(args):
+ val_dataset = Kitti(data_root=args.data_root,
+ split='val')
+ val_dataloader = get_dataloader(dataset=val_dataset,
+ batch_size=args.batch_size,
+ num_workers=args.num_workers,
+ shuffle=False)
+ CLASSES = Kitti.CLASSES
+ LABEL2CLASSES = {v:k for k, v in CLASSES.items()}
+
+ if not args.no_cuda:
+ model = PointPillars(nclasses=args.nclasses).cuda()
+ model.load_state_dict(torch.load(args.ckpt))
+ else:
+ model = PointPillars(nclasses=args.nclasses)
+ model.load_state_dict(
+ torch.load(args.ckpt, map_location=torch.device('cpu')))
+
+ saved_path = args.saved_path
+ os.makedirs(saved_path, exist_ok=True)
+ saved_submit_path = os.path.join(saved_path, 'submit')
+ os.makedirs(saved_submit_path, exist_ok=True)
+
+ pcd_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32)
+
+ model.eval()
+ with torch.no_grad():
+ format_results = {}
+ print('Predicting and Formatting the results.')
+ for i, data_dict in enumerate(tqdm(val_dataloader)):
+ if not args.no_cuda:
+ # move the tensors to the cuda
+ for key in data_dict:
+ for j, item in enumerate(data_dict[key]):
+ if torch.is_tensor(item):
+ data_dict[key][j] = data_dict[key][j].cuda()
+
+ batched_pts = data_dict['batched_pts']
+ batched_gt_bboxes = data_dict['batched_gt_bboxes']
+ batched_labels = data_dict['batched_labels']
+ batched_difficulty = data_dict['batched_difficulty']
+ batch_results = model(batched_pts=batched_pts,
+ mode='val',
+ batched_gt_bboxes=batched_gt_bboxes,
+ batched_gt_labels=batched_labels)
+ # pdb.set_trace()
+ for j, result in enumerate(batch_results):
+ format_result = {
+ 'name': [],
+ 'truncated': [],
+ 'occluded': [],
+ 'alpha': [],
+ 'bbox': [],
+ 'dimensions': [],
+ 'location': [],
+ 'rotation_y': [],
+ 'score': []
+ }
+
+ calib_info = data_dict['batched_calib_info'][j]
+ tr_velo_to_cam = calib_info['Tr_velo_to_cam'].astype(np.float32)
+ r0_rect = calib_info['R0_rect'].astype(np.float32)
+ P2 = calib_info['P2'].astype(np.float32)
+ image_shape = data_dict['batched_img_info'][j]['image_shape']
+ idx = data_dict['batched_img_info'][j]['image_idx']
+ result_filter = keep_bbox_from_image_range(result, tr_velo_to_cam, r0_rect, P2, image_shape)
+ result_filter = keep_bbox_from_lidar_range(result_filter, pcd_limit_range)
+
+ lidar_bboxes = result_filter['lidar_bboxes']
+ labels, scores = result_filter['labels'], result_filter['scores']
+ bboxes2d, camera_bboxes = result_filter['bboxes2d'], result_filter['camera_bboxes']
+ for lidar_bbox, label, score, bbox2d, camera_bbox in \
+ zip(lidar_bboxes, labels, scores, bboxes2d, camera_bboxes):
+ format_result['name'].append(LABEL2CLASSES[label])
+ format_result['truncated'].append(0.0)
+ format_result['occluded'].append(0)
+ alpha = camera_bbox[6] - np.arctan2(camera_bbox[0], camera_bbox[2])
+ format_result['alpha'].append(alpha)
+ format_result['bbox'].append(bbox2d)
+ format_result['dimensions'].append(camera_bbox[3:6])
+ format_result['location'].append(camera_bbox[:3])
+ format_result['rotation_y'].append(camera_bbox[6])
+ format_result['score'].append(score)
+
+ write_label(format_result, os.path.join(saved_submit_path, f'{idx:06d}.txt'))
+
+ format_results[idx] = {k:np.array(v) for k, v in format_result.items()}
+
+ write_pickle(format_results, os.path.join(saved_path, 'results.pkl'))
+
+ print('Evaluating.. Please wait several seconds.')
+ do_eval(format_results, val_dataset.data_infos, CLASSES, saved_path)
+
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser(description='Configuration Parameters')
+ parser.add_argument('--data_root', default='/mnt/ssd1/lifa_rdata/det/kitti',
+ help='your data root for kitti')
+ parser.add_argument('--ckpt', default='pretrained/epoch_160.pth', help='your checkpoint for kitti')
+ parser.add_argument('--saved_path', default='results', help='your saved path for predicted results')
+ parser.add_argument('--batch_size', type=int, default=1)
+ parser.add_argument('--num_workers', type=int, default=4)
+ parser.add_argument('--nclasses', type=int, default=3)
+ parser.add_argument('--no_cuda', action='store_true',
+ help='whether to use cuda')
+ args = parser.parse_args()
+
+ main(args)
diff --git a/notebooks/3D-point-pillars/export_ov_e2e.py b/notebooks/3D-point-pillars/export_ov_e2e.py
new file mode 100644
index 00000000000..b4e00de0bf0
--- /dev/null
+++ b/notebooks/3D-point-pillars/export_ov_e2e.py
@@ -0,0 +1,478 @@
+"""
+Export PointPillars model to OpenVINO IR with custom voxelization op configuration
+Usage: python export_ov_e2e.py --checkpoint pretrained/epoch_160.pth --output pretrained/pointpillars_full
+"""
+
+import argparse
+import os
+import sys
+import json
+import torch
+import torch.nn as nn
+import openvino as ov
+
+from pointpillars.model import PointPillars
+
+
+class NeuralNetworkPortion(nn.Module):
+ """Neural network portion: PillarEncoder + Backbone + Neck + Head"""
+
+ def __init__(self, model):
+ super().__init__()
+ self.pillar_encoder = model.pillar_encoder
+ self.backbone = model.backbone
+ self.neck = model.neck
+ self.head = model.head
+
+ def forward(self, pillars, coors, npoints):
+ pillar_features = self.pillar_encoder(pillars, coors, npoints)
+ xs = self.backbone(pillar_features)
+ x = self.neck(xs)
+ cls_preds, box_preds, dir_cls_preds = self.head(x)
+ return cls_preds, box_preds, dir_cls_preds
+
+
+def create_pillar_layer_ir(voxel_params, output_path):
+ """Create and save PillarLayer IR model with VoxelizationOp"""
+
+ max_voxels = int(voxel_params['max_voxels'])
+ max_points = int(voxel_params['max_num_points'])
+ voxel_size_str = ",".join(map(str, voxel_params['voxel_size']))
+ pc_range_str = ",".join(map(str, voxel_params['point_cloud_range']))
+
+ xml_content = f"""
+
+
+
+
+
+
+
+
+
+
+ -1
+ 4
+
+
+
+
+
+
+
+ -1
+ {max_points}
+ 4
+
+
+
+
+
+
+ -1
+ 4
+
+
+
+
+
+
+ -1
+
+
+
+
+
+
+
+
+
+
+
+"""
+
+ pillar_layer_xml_path = output_path + "_pillar_layer.xml"
+ with open(pillar_layer_xml_path, 'w') as f:
+ f.write(xml_content)
+
+ print(f"✓ PillarLayer IR saved: {pillar_layer_xml_path}")
+ return pillar_layer_xml_path
+
+
+def create_postprocessing_ir(postproc_params, output_path):
+ """
+ Create post-processing IR using custom PostProcessingOp extension.
+
+ This creates an OpenVINO IR XML that wraps:
+ 1. Anchor generation (dynamic based on feature map size)
+ 2. BBox decoding (anchors2bboxes transformation)
+ 3. Per-class NMS with rotated IoU
+ 4. Direction classification
+
+ The PostProcessingOp is implemented in ov_extensions/postprocessing_op.cpp
+ """
+
+ print("Creating post-processing IR with PostProcessingOp extension...")
+
+ # Get model configuration
+ ranges = postproc_params['anchors_ranges']
+ sizes = postproc_params['anchors_sizes']
+ rotations = postproc_params['anchors_rotations']
+
+ # Get post-processing parameters
+ nclasses = postproc_params['nclasses']
+ nms_pre = postproc_params['nms_pre']
+ score_thr = postproc_params['score_thr']
+ nms_thr = postproc_params['nms_thr']
+ max_num = postproc_params['max_num']
+
+ # Create XML content
+ xml_content = f'''
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -1
+ -1
+ -1
+
+
+ -1
+ -1
+ -1
+
+
+ -1
+ -1
+ -1
+
+
+
+
+
+
+
+ -1
+ 7
+
+
+
+
+
+
+ -1
+
+
+
+
+
+
+ -1
+
+
+
+
+
+
+
+
+
+
+
+
+
+'''
+
+ # Write XML file
+ xml_path = output_path + "_postproc.xml"
+ with open(xml_path, 'w') as f:
+ f.write(xml_content)
+
+ print(f"✓ Post-processing IR saved to: {xml_path}")
+ print(f" - Inputs: bbox_cls_pred, bbox_pred, bbox_dir_cls_pred (from NN head)")
+ print(f" - Outputs: bboxes [k,7], labels [k], scores [k]")
+ print(f" - NMS pre: {nms_pre}, Score threshold: {score_thr}, NMS IoU threshold: {nms_thr}, Max detections: {max_num}")
+
+ return xml_path
+
+
+def export_full_model_to_openvino(checkpoint_path, output_path):
+ """Export PointPillars to OpenVINO with custom voxelization op support"""
+
+ print(f"Loading PyTorch checkpoint: {checkpoint_path}")
+ full_model = PointPillars()
+ checkpoint = torch.load(checkpoint_path, map_location='cpu', weights_only=False)
+ full_model.load_state_dict(checkpoint)
+ full_model.eval()
+
+ # Export neural network portion
+ print("Exporting neural network (PillarEncoder + Backbone + Neck + Head)...")
+ nn_portion = NeuralNetworkPortion(full_model)
+
+ ov_nn_model = None
+
+ # Extract voxelization parameters
+ voxel_params = {
+ 'voxel_size': full_model.pillar_layer.voxel_layer.voxel_size if args.voxel_size_str is None else [float(v) for v in args.voxel_size_str.split(',')],
+ 'point_cloud_range': full_model.pillar_layer.voxel_layer.point_cloud_range if args.pc_range_str is None else [float(v) for v in args.pc_range_str.split(',')],
+ 'max_num_points': full_model.pillar_layer.voxel_layer.max_num_points if args.max_points is None else int(args.max_points),
+ 'max_voxels': full_model.pillar_layer.voxel_layer.max_voxels[0] if args.max_voxels is None else int(args.max_voxels)
+ }
+
+ max_voxels = voxel_params['max_voxels']
+ max_points = voxel_params['max_num_points']
+ voxel_size = voxel_params['voxel_size']
+ point_cloud_range = voxel_params['point_cloud_range']
+
+ dummy_pillars = torch.randn(max_voxels, max_points, 4)
+
+ vx, vy, vz = voxel_size[0], voxel_size[1], voxel_size[2]
+ x_l = int((point_cloud_range[3] - point_cloud_range[0]) / vx)
+ y_l = int((point_cloud_range[4] - point_cloud_range[1]) / vy)
+ z_l = int((point_cloud_range[5] - point_cloud_range[2]) / vz)
+ dummy_coors = torch.empty((max_voxels, 4), dtype=torch.long)
+ dummy_coors[:, 0] = 0 # batch index
+ if z_l > 0:
+ dummy_coors[:, 1] = torch.randint(0, z_l, (max_voxels,))
+ else:
+ dummy_coors[:, 1] = 0
+ dummy_coors[:, 2] = torch.randint(0, y_l, (max_voxels,))
+ dummy_coors[:, 3] = torch.randint(0, x_l, (max_voxels,))
+
+ dummy_npoints = torch.randint(1, max_points, (max_voxels,)).long()
+
+ if ov_nn_model is None:
+ # Convert directly from PyTorch to OpenVINO (bypasses ONNX entirely)
+ # Use torch.jit.trace with check_trace=False to suppress warnings from
+ # non-deterministic scatter operations in PillarEncoder
+ import warnings
+ try:
+ with torch.no_grad(), warnings.catch_warnings():
+ warnings.filterwarnings("ignore", category=torch.jit.TracerWarning)
+ traced_nn = torch.jit.trace(
+ nn_portion,
+ (dummy_pillars, dummy_coors, dummy_npoints),
+ check_trace=False,
+ strict=False
+ )
+ ov_nn_model = ov.convert_model(
+ traced_nn,
+ example_input=(dummy_pillars, dummy_coors, dummy_npoints),
+ input=[
+ ov.PartialShape([-1, max_points, 4]), # pillars
+ ov.PartialShape([-1, 4]), # coors
+ ov.PartialShape([-1]), # npoints
+ ]
+ )
+ print("✓ PyTorch model converted to OpenVINO IR directly")
+ except Exception as e:
+ print(f"✗ Direct conversion failed: {e}")
+
+ # if ov_nn_model is None:
+ # # Trace directly is also throwing warnings:
+ # # traced function is producing different numeric outputs from
+ # # the original Python function on the same inputs
+ # #
+ # with torch.no_grad():
+ # traced_nn = torch.jit.trace(nn_portion, (dummy_pillars, dummy_coors, dummy_npoints), check_trace=True)
+ # ov_nn_model = ov.convert_model(traced_nn, example_input=(dummy_pillars, dummy_coors, dummy_npoints))
+
+ if ov_nn_model is not None:
+ nn_xml_path = output_path + "_nn.xml"
+ ov.save_model(ov_nn_model, nn_xml_path)
+ print(f"✓ Neural network IR saved: {nn_xml_path}")
+ else:
+ print("✗ Neural network IR conversion failed:")
+ return -1
+
+ # Create PillarLayer IR model
+ print("Creating PillarLayer IR model with VoxelizationOp...")
+ pillar_layer_xml_path = create_pillar_layer_ir(voxel_params, output_path)
+
+ # Get post-processing parameters
+ postproc_params = {
+ 'nclasses': full_model.nclasses if args.nclasses is None else int(args.nclasses),
+ 'nms_pre': full_model.nms_pre if args.nms_pre is None else int(args.nms_pre),
+ 'score_thr': full_model.score_thr if args.score_thr is None else float(args.score_thr),
+ 'nms_thr': full_model.nms_thr if args.nms_thr is None else float(args.nms_thr),
+ 'max_num': full_model.max_num if args.max_num is None else int(args.max_num),
+ # anchors_ranges/sizes stored here as flat lists of floats to match create_postprocessing_ir expectations
+ 'anchors_ranges': (
+ [v for r in full_model.anchors_generator.ranges for v in r]
+ if args.anchors_ranges is None
+ else [float(v) for v in args.anchors_ranges.split(',')]
+ ),
+ 'anchors_sizes': (
+ [v for s in full_model.anchors_generator.sizes for v in s]
+ if args.anchors_sizes is None
+ else [float(v) for v in args.anchors_sizes.split(',')]
+ ),
+ 'anchors_rotations': (
+ list(full_model.anchors_generator.rotations)
+ if args.anchors_rotations is None
+ else [float(v) for v in args.anchors_rotations.split(',')]
+ ),
+ }
+
+ # Create Post-processing IR model
+ postproc_xml_path = create_postprocessing_ir(postproc_params, output_path)
+
+ extension_lib_path = args.extension_lib
+
+ if not os.path.exists(extension_lib_path):
+ print(f"ERROR: OpenVINO extension library not found at {extension_lib_path}")
+ print("Build the extension: cd ov_extensions && bash build.sh")
+ return None
+
+ # Save configuration
+ config = {
+ 'voxel_params': voxel_params,
+ 'extension_lib': extension_lib_path,
+ 'voxel_model': pillar_layer_xml_path,
+ 'nn_model': nn_xml_path,
+ 'postproc_model': postproc_xml_path
+ }
+
+ config_path = output_path + "_config.json"
+ with open(config_path, 'w') as f:
+ json.dump(config, f, indent=2)
+ print(f"✓ Configuration saved: {config_path}")
+
+ print("\n" + "="*70)
+ print("EXPORT COMPLETE - Full OpenVINO Pipeline")
+ print("="*70)
+ print("Components:")
+ print(f" 1. PillarLayer IR: {pillar_layer_xml_path}")
+ print(f" 2. Neural Network IR: {nn_xml_path}")
+ print(f" 3. Post-processing IR: {postproc_xml_path}")
+ print(f" 4. Configuration: {config_path}")
+ print(f" 5. Custom Extension: {extension_lib_path}")
+ print("\nModel architecture:")
+ print(" - Pillar Layer (voxelization) → Custom OpenVINO Op")
+ print(" - PillarEncoder → OpenVINO IR")
+ print(" - Backbone → OpenVINO IR")
+ print(" - Neck → OpenVINO IR")
+ print(" - Head → OpenVINO IR")
+ print(" - Post-processing (Anchors + BBox Decode + Rotated NMS) → Custom OpenVINO Op")
+ print("\nRuntime usage:")
+ print(" core = ov.Core()")
+ print(f" core.add_extension('{extension_lib_path}')")
+ print(f" pillar_layer_model = core.read_model('{pillar_layer_xml_path}')")
+ print(f" nn_model = core.read_model('{nn_xml_path}')")
+ print(f" postproc_model = core.read_model('{postproc_xml_path}')")
+ print("="*70)
+
+ return True
+
+
+if __name__ == "__main__":
+ current_file_path = os.path.dirname(os.path.abspath(__file__))
+ parser = argparse.ArgumentParser(description='Export PointPillars to OpenVINO')
+ parser.add_argument('--checkpoint', type=str,
+ default=f'{current_file_path}/pretrained/epoch_160.pth',
+ help='Path to PyTorch checkpoint (.pth)')
+ parser.add_argument('--output', type=str,
+ default=f'{current_file_path}/pretrained/pointpillars_ov',
+ help='Output path (without extension)')
+ # Path to compiled OpenVINO extension library for custom ops
+ parser.add_argument('--extension-lib', dest='extension_lib', type=str,
+ default=f'{current_file_path}/ov_extensions/build/libov_pointpillars_extensions.so',
+ help=f'Path to OpenVINO extension lib (default: {current_file_path}/ov_extensions/build/libov_pointpillars_extensions.so)')
+ # Voxelization and point-cloud parameters (model-dependent)
+ parser.add_argument('--max-voxels', dest='max_voxels', type=int, default=None,
+ help='Maximum number of voxels (default: 16000, from PointPillars model description)')
+ parser.add_argument('--max-points', dest='max_points', type=int, default=None,
+ help='Maximum number of points per voxel (default: 32, from PointPillars model description)')
+ parser.add_argument('--voxel-size-str', dest='voxel_size_str', type=str, default=None,
+ help='Voxel size as comma-separated string, default: "0.16,0.16,4", from PointPillars model description')
+ parser.add_argument('--pc-range-str', dest='pc_range_str', type=str,
+ default=None,
+ help='Point cloud range as comma-separated string, "x_min,y_min,z_min,x_max,y_max,z_max", default: "0,-39.68,-3,69.12,39.68,1", from PointPillars model description')
+ # Post-processing parameters (model-dependent)
+ parser.add_argument('--nclasses', dest='nclasses', type=int, default=None,
+ help='Number of classes (default: 3, from PointPillars model description)')
+ parser.add_argument('--nms-pre', dest='nms_pre', type=int, default=None,
+ help='Number of pre-NMS top proposals to keep (default: 100, from PointPillars model description)')
+ parser.add_argument('--score-thr', dest='score_thr', type=float, default=None,
+ help='Score threshold for detections (default: 0.1, from PointPillars model description)')
+ parser.add_argument('--nms-thr', dest='nms_thr', type=float, default=None,
+ help='NMS IoU threshold (default: 0.01, from PointPillars model description)')
+ parser.add_argument('--max-num', dest='max_num', type=int, default=None,
+ help='Maximum number of final detections (default: 50, from PointPillars model description)')
+ # Anchor configuration (comma-separated values)
+ parser.add_argument('--anchors-ranges', dest='anchors_ranges', type=str,
+ default=None,
+ help='Anchors ranges as comma-separated floats (default, from PointPillars model description: "0,-39.68,-0.6,69.12,39.68,-0.6,0,-39.68,-0.6,69.12,39.68,-0.6,0,-39.68,-1.78,69.12,39.68,-1.78")')
+ parser.add_argument('--anchors-sizes', dest='anchors_sizes', type=str,
+ default=None,
+ help='Anchors sizes as comma-separated floats (default, from PointPillars model description: "0.6,0.8,1.73,0.6,1.76,1.73,1.6,3.9,1.56")')
+ parser.add_argument('--anchors-rotations', dest='anchors_rotations', type=str,
+ default=None,
+ help='Anchors rotations as comma-separated floats (default, from PointPillars model description: "0,1.57")')
+
+ args = parser.parse_args()
+ export_full_model_to_openvino(args.checkpoint, args.output)
diff --git a/notebooks/3D-point-pillars/figures/img_3dbbox_000134.png b/notebooks/3D-point-pillars/figures/img_3dbbox_000134.png
new file mode 100644
index 00000000000..0562a3759a6
Binary files /dev/null and b/notebooks/3D-point-pillars/figures/img_3dbbox_000134.png differ
diff --git a/notebooks/3D-point-pillars/figures/pc_pred_000134.png b/notebooks/3D-point-pillars/figures/pc_pred_000134.png
new file mode 100644
index 00000000000..9071d66b763
Binary files /dev/null and b/notebooks/3D-point-pillars/figures/pc_pred_000134.png differ
diff --git a/notebooks/3D-point-pillars/figures/pytorch_trt.png b/notebooks/3D-point-pillars/figures/pytorch_trt.png
new file mode 100755
index 00000000000..443f28e8dc6
Binary files /dev/null and b/notebooks/3D-point-pillars/figures/pytorch_trt.png differ
diff --git a/notebooks/3D-point-pillars/misc/log.md b/notebooks/3D-point-pillars/misc/log.md
new file mode 100644
index 00000000000..280d0445bd2
--- /dev/null
+++ b/notebooks/3D-point-pillars/misc/log.md
@@ -0,0 +1,103 @@
+- 难点: 碰撞检测
+- 代码难点: nms
+
+## Datasets
+
+- database 随机采样增强
+ - 核心: 碰撞检测, 点是否在立方体内
+ - 输入: gt_bboxes_3d, pts, gt_labels
+ - 输出: gt_bboxes_3d, pts, gt_labels
+ - 逻辑:
+ 1. 从Car, Pedestrian, Cyclist的database数据集中随机采集一定数量的bbox及inside points, 使每类bboxes的数量分别达到15, 10, 10.
+ 2. 将这些采样的bboxes进行碰撞检测, 满足碰撞检测的bboxes和对应labels加到gt_bboxes_3d, gt_labels
+ 3. 把位于这些采样bboxes内点删除掉, 替换成bboxes内部的点.
+- object 随机旋转平移
+ - 核心: 碰撞检测, 点是否在立方体内
+ - 输入: gt_bboxes_3d, pts
+ - 输出: gt_bboxes_3d, pts
+ - 逻辑:
+ 1. 以某个bbox为例, 随机产生num_try个平移向量t和旋转角度r, 旋转角度可以转成旋转矩阵(mat).
+ 2. 对bbox进行旋转和平移, 找到num_try中第一个通过碰撞测试的平移向量t和旋转角度r(mat).
+ 3. 对bbox内部的点进行旋转和平移.
+ 4. 对bbox进行旋转和平移.
+- 整体随机水平翻转
+ - object: 水平翻转 (注意角度)
+ - point: 水平翻转
+- 整体旋转, 缩放和平移
+ - object: 旋转, 缩放和平移, object的旋转需要注意, (x, y, z)和angle都需要变化.
+ - point: 旋转, 缩放和平移
+- 删除范围外的point
+- 删除范围外的bbox
+ - 需要注意的是: 这里做了旋转角度的归一化 (-pi, pi)
+- point shuffle
+- dataloader实现, `目前为了调试shuffle设置成了False, 之后需要设置成True`
+
+## Model
+
+- Pillar
+ - cuda拓展
+ ```
+ cd ops
+ python setup.py develop
+ ```
+ - Voxelization类实现, 这里基本是从mmdet3d复制过来的; 修改了`coors_out`的顺序 (z, y, x) -> (x, y, z)
+ - PillarLayer: 整合batch数据整pillars
+ - PillarEncoder: pillar 编码((N, 4) -> (N, 9) -> (1, 64))
+ - PillarScatter
+- Backbone
+ - 完成
+ - nn.init.kaiming_normal_初始化方式 (`删除cuda seed`)
+- Neck
+ - 完成
+ - nn.init.kaiming_normal_初始化方式 (`删除cuda seed`)
+- Head
+ - 完成
+ - nn.init.normal_(m.weight, mean=0, std=0.01)初始化方式 (`删除cuda seed`)
+
+## Bbox (bottom center for z)
+
+- Anchor
+ - 生成完成
+- 编码, 解码完成
+- iou3d (完成)
+ - bev overlap
+ - height overlap
+ - iou3d
+- anchor生成label
+
+## Train
+
+- loss
+ - cls loss
+ - pos: 与0, 1, 2类bboxes具有很大iou(大于某个阈值)的anchors; 与0, 1, 2类具有最大iou的anchors.
+ - neg: 与任何bboxes最有非常小iou(小于某个阈值)的anchors; 与-1类bboxes具有很大iou或者最大iou的anchors.
+ - reg loss
+ - 训练样本: 与0, 1, 2类bboxes具有很大iou(大于某个阈值)的anchors; 与0, 1, 2类具有最大iou的anchors.
+ - dir cls loss
+ - 训练样本: 与0, 1, 2类bboxes具有很大iou(大于某个阈值)的anchors; 与0, 1, 2类具有最大iou的anchors.
+- 优化器
+- 开始训练
+
+## Test and evaluate
+
+- 预测bbox
+- 可视化
+- 评估
+ - label_2的格式, mmdet3d .pkl的格式
+ - iou 计算(bbox, bev, 3dbbox)
+ - gt_bbox, dt_bbox分类 (ignore, normal, remove)
+ - 基于tp, 计算score threshold
+ - 计算precision, recall
+ - 计算AP, mAP
+- 性能优化
+- 代码优化 (不急)
+
+## bbox property evaluation
+
+以 `label='Pedestrian', difficulty=1`为例,
+
+| ignore level | gt | det |
+|:---:|:---:|:---:|
+| 1 | (cur_label == 'Pedestrian' && cur_difficulty > 1) or cur_label == 'Person_sitting' | cur_heigh < MIN_HEIGHTS[1] |
+| 0 | cur_label == 'Pedestrian' && cur_difficulty <= 1 | cur_label == 'Pedestrian' |
+| - 1 | Others | Others |
diff --git a/notebooks/3D-point-pillars/misc/vis_data_gt.py b/notebooks/3D-point-pillars/misc/vis_data_gt.py
new file mode 100644
index 00000000000..741a010ebaa
--- /dev/null
+++ b/notebooks/3D-point-pillars/misc/vis_data_gt.py
@@ -0,0 +1,84 @@
+import argparse
+from ast import arg
+import cv2
+import copy
+import numpy as np
+import os
+import sys
+
+from yaml import parse
+CUR = os.path.dirname(os.path.abspath(__file__))
+sys.path.append(os.path.dirname(CUR))
+from utils import read_points, read_calib, read_label, bbox_camera2lidar, vis_pc, bbox3d2corners,\
+ points_lidar2image, vis_img_3d
+
+
+def vis_gt(root, id, saved_root):
+ img_path = os.path.join(root, 'image_2', f'{id}.png')
+ lidar_path = os.path.join(root, 'velodyne', f'{id}.bin')
+ calib_path = os.path.join(root, 'calib', f'{id}.txt')
+ label_path = os.path.join(root, 'label_2', f'{id}.txt')
+
+ img = cv2.imread(img_path)
+ img3d = copy.deepcopy(img)
+ lidar_points = read_points(lidar_path)
+ calib_dict = read_calib(calib_path)
+ annotation_dict = read_label(label_path)
+
+ bboxes = annotation_dict['bbox']
+ names = annotation_dict['name']
+ colors = [[0, 0, 255], [0, 255, 0], [255, 0, 0], [255, 255, 0]]
+ CLASSES = {
+ 'Pedestrian': 0,
+ 'Cyclist': 1,
+ 'Car': 2
+ }
+
+
+ ## 1. visualize 2d
+ for i, bbox in enumerate(bboxes):
+ x1, y1, x2, y2 = bbox
+ x1, y1, x2, y2 = int(x1), int(y1), int(x2), int(y2)
+ cv2.rectangle(img, (x1, y1), (x2, y2), colors[CLASSES.get(names[i], -1)], 2)
+ cv2.imwrite(os.path.join(saved_root, f'{id}-2d.png'), img)
+ cv2.imshow(f'{id}-2d bbox', img)
+ cv2.waitKey(0)
+
+ ## 2. visualize 3d bbox in point cloud
+
+ # 2.1 camera coordinates
+ dimensions = annotation_dict['dimensions']
+ location = annotation_dict['location']
+ rotation_y = annotation_dict['rotation_y']
+ names = annotation_dict['name']
+
+ # 2.2 lidar coordinates
+ bboxes_camera = np.concatenate([location, dimensions, rotation_y[:, None]], axis=-1)
+ tr_velo_to_cam = calib_dict['Tr_velo_to_cam']
+ r0_rect = calib_dict['R0_rect']
+ bboxes_lidar = bbox_camera2lidar(bboxes_camera, tr_velo_to_cam, r0_rect)
+ lidar_bboxes_points = bbox3d2corners(bboxes_lidar) # (N, 8, 3)
+ labels = [CLASSES.get(name, -1) for name in names]
+ vis_pc(lidar_points, lidar_bboxes_points, labels) # (N, 8, 2)
+
+ ## 3. visualize 3d bbox in image
+ P2 = calib_dict['P2']
+ image_points = points_lidar2image(lidar_bboxes_points, tr_velo_to_cam, r0_rect, P2)
+ img3d = vis_img_3d(img3d, image_points, labels)
+ cv2.imwrite(os.path.join(saved_root, f'{id}-3d.png'), img3d)
+ cv2.imshow(f'{id}-3d bbox', img3d)
+ cv2.waitKey(0)
+
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser(description='Data information')
+ parser.add_argument('--root', default='/home/lifa/data/KITTI/training')
+ parser.add_argument('--id', default='000134')
+ parser.add_argument('--saved_root', default='tmp')
+ args = parser.parse_args()
+
+ root = args.root
+ id = args.id
+ saved_root = args.saved_root
+ os.makedirs(saved_root, exist_ok=True)
+ vis_gt(root, id, saved_root)
diff --git a/notebooks/3D-point-pillars/ov_extensions/CMakeLists.txt b/notebooks/3D-point-pillars/ov_extensions/CMakeLists.txt
new file mode 100644
index 00000000000..60e8dab7082
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/CMakeLists.txt
@@ -0,0 +1,40 @@
+cmake_minimum_required(VERSION 3.13)
+
+project(ov_pointpillars_extensions)
+
+set(CMAKE_CXX_STANDARD 17)
+set(CMAKE_CXX_STANDARD_REQUIRED ON)
+
+# Find OpenVINO
+find_package(OpenVINO REQUIRED COMPONENTS Runtime)
+
+# Source files
+set(SOURCES
+ iou3d_utils.cpp
+ voxelization_op.cpp
+ postprocessing_op.cpp
+ ov_pointpillars_ext.cpp
+)
+
+set(HEADERS
+ iou3d_utils.hpp
+ voxelization_op.hpp
+ postprocessing_op.hpp
+)
+
+# Build shared library
+add_library(ov_pointpillars_extensions SHARED ${SOURCES} ${HEADERS})
+
+target_link_libraries(ov_pointpillars_extensions PRIVATE openvino::runtime)
+
+# Set output directory
+set_target_properties(ov_pointpillars_extensions PROPERTIES
+ LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
+ RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
+)
+
+# Install
+install(TARGETS ov_pointpillars_extensions
+ LIBRARY DESTINATION lib
+ RUNTIME DESTINATION bin
+)
diff --git a/notebooks/3D-point-pillars/ov_extensions/build.sh b/notebooks/3D-point-pillars/ov_extensions/build.sh
new file mode 100755
index 00000000000..fdb25c3b72f
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/build.sh
@@ -0,0 +1,30 @@
+#!/bin/bash
+# Build OpenVINO PointPillars extensions
+
+set -e
+
+BUILD_TYPE=${1:-Release}
+SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)"
+BUILD_DIR="${SCRIPT_DIR}/build"
+
+# Create build directory
+mkdir -p "${BUILD_DIR}"
+cd "${BUILD_DIR}"
+
+# Find OpenVINO installation
+OPENVINO_DIR=$(python -c "import openvino; import os; print(os.path.dirname(openvino.__file__))")
+
+# Configure and build
+cmake .. \
+ -DCMAKE_BUILD_TYPE=${BUILD_TYPE} \
+ -DCMAKE_CXX_FLAGS="-fPIC" \
+ -DOpenVINO_DIR="${OPENVINO_DIR}/cmake"
+
+if make -j$(nproc); then
+ echo "✓ OpenVINO extensions built successfully"
+ echo " Library: ${BUILD_DIR}/libov_pointpillars_extensions.so"
+else
+ rc=$?
+ echo "Failed to build OpenVINO extensions (exit code: ${rc})" >&2
+ exit ${rc}
+fi
diff --git a/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.cpp b/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.cpp
new file mode 100644
index 00000000000..3c6b818a31c
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.cpp
@@ -0,0 +1,195 @@
+// Shared IoU 3D utility functions
+#include "iou3d_utils.hpp"
+// Modified from
+// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu
+// https://github.com/zhulf0804/PointPillars/blob/main/pointpillars/ops/iou3d/iou3d_kernel.cu
+
+/*
+3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)
+Written by Shaoshuai Shi
+All Rights Reserved 2019-2020.
+*/
+
+#include
+#include
+#include
+
+static constexpr float EPS = 1e-8f;
+
+struct Point {
+ float x, y;
+ Point() : x(0), y(0) {}
+ Point(float _x, float _y) : x(_x), y(_y) {}
+ void set(float _x, float _y) {
+ x = _x;
+ y = _y;
+ }
+ Point operator+(const Point &b) const { return Point(x + b.x, y + b.y); }
+ Point operator-(const Point &b) const { return Point(x - b.x, y - b.y); }
+};
+
+inline float cross(const Point &a, const Point &b) {
+ return a.x * b.y - a.y * b.x;
+}
+
+inline float cross(const Point &p1, const Point &p2, const Point &p0) {
+ return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y);
+}
+
+inline int check_rect_cross(const Point &p1, const Point &p2, const Point &q1,
+ const Point &q2) {
+ int ret = std::min(p1.x, p2.x) <= std::max(q1.x, q2.x) &&
+ std::min(q1.x, q2.x) <= std::max(p1.x, p2.x) &&
+ std::min(p1.y, p2.y) <= std::max(q1.y, q2.y) &&
+ std::min(q1.y, q2.y) <= std::max(p1.y, p2.y);
+ return ret;
+}
+
+inline int check_in_box2d(const float *box, const Point &p) {
+ const float MARGIN = 1e-5f;
+ float center_x = (box[0] + box[2]) / 2.f;
+ float center_y = (box[1] + box[3]) / 2.f;
+ float angle_cos = std::cos(-box[4]), angle_sin = std::sin(-box[4]);
+ float rot_x =
+ (p.x - center_x) * angle_cos + (p.y - center_y) * angle_sin + center_x;
+ float rot_y =
+ -(p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos + center_y;
+ return (rot_x > box[0] - MARGIN && rot_x < box[2] + MARGIN &&
+ rot_y > box[1] - MARGIN && rot_y < box[3] + MARGIN);
+}
+
+inline int intersection(const Point &p1, const Point &p0, const Point &q1,
+ const Point &q0, Point &ans) {
+ if (check_rect_cross(p0, p1, q0, q1) == 0)
+ return 0;
+ float s1 = cross(q0, p1, p0);
+ float s2 = cross(p1, q1, p0);
+ float s3 = cross(p0, q1, q0);
+ float s4 = cross(q1, p1, q0);
+ if (!(s1 * s2 > 0 && s3 * s4 > 0))
+ return 0;
+
+ float s5 = cross(q1, p1, p0);
+ if (std::fabs(s5 - s1) > EPS) {
+ ans.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1);
+ ans.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1);
+ } else {
+ float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y;
+ float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y;
+ float D = a0 * b1 - a1 * b0;
+ // If D == 0 lines are parallel; avoid division by zero: // Extra
+ if (std::fabs(D) < EPS) { // Extra
+ // fallback: use midpoint of overlapping segment // Extra
+ ans.x = (p0.x + p1.x + q0.x + q1.x) * 0.25f; // Extra
+ ans.y = (p0.y + p1.y + q0.y + q1.y) * 0.25f; // Extra
+ } else { // Extra
+ ans.x = (b0 * c1 - b1 * c0) / D;
+ ans.y = (a1 * c0 - a0 * c1) / D;
+ } // Extra
+ }
+ return 1;
+}
+
+inline void rotate_around_center(const Point ¢er, const float angle_cos,
+ const float angle_sin, Point &p) {
+ float new_x =
+ (p.x - center.x) * angle_cos + (p.y - center.y) * angle_sin + center.x;
+ float new_y =
+ -(p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y;
+ p.set(new_x, new_y);
+}
+
+inline bool point_cmp(const Point &a, const Point &b, const Point ¢er) {
+ return std::atan2(a.y - center.y, a.x - center.x) >
+ std::atan2(b.y - center.y, b.x - center.x);
+}
+
+float box_overlap(const float *box_a, const float *box_b) {
+ float a_x1 = box_a[0], a_y1 = box_a[1], a_x2 = box_a[2], a_y2 = box_a[3],
+ a_angle = box_a[4];
+ float b_x1 = box_b[0], b_y1 = box_b[1], b_x2 = box_b[2], b_y2 = box_b[3],
+ b_angle = box_b[4];
+
+ Point center_a((a_x1 + a_x2) / 2.f, (a_y1 + a_y2) / 2.f);
+ Point center_b((b_x1 + b_x2) / 2.f, (b_y1 + b_y2) / 2.f);
+
+ Point box_a_corners[5];
+ box_a_corners[0].set(a_x1, a_y1);
+ box_a_corners[1].set(a_x2, a_y1);
+ box_a_corners[2].set(a_x2, a_y2);
+ box_a_corners[3].set(a_x1, a_y2);
+
+ Point box_b_corners[5];
+ box_b_corners[0].set(b_x1, b_y1);
+ box_b_corners[1].set(b_x2, b_y1);
+ box_b_corners[2].set(b_x2, b_y2);
+ box_b_corners[3].set(b_x1, b_y2);
+
+ float a_angle_cos = std::cos(a_angle), a_angle_sin = std::sin(a_angle);
+ float b_angle_cos = std::cos(b_angle), b_angle_sin = std::sin(b_angle);
+
+ for (int k = 0; k < 4; k++) {
+ rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]);
+ rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]);
+ }
+ box_a_corners[4] = box_a_corners[0];
+ box_b_corners[4] = box_b_corners[0];
+
+ Point cross_points[16];
+ Point poly_center;
+ int cnt = 0, flag = 0;
+ poly_center.set(0, 0);
+
+ for (int i = 0; i < 4; i++) {
+ for (int j = 0; j < 4; j++) {
+ flag = intersection(box_a_corners[i + 1], box_a_corners[i],
+ box_b_corners[j + 1], box_b_corners[j],
+ cross_points[cnt]);
+ if (flag) {
+ poly_center = poly_center + cross_points[cnt];
+ cnt++;
+ }
+ }
+ }
+
+ for (int k = 0; k < 4; k++) {
+ if (check_in_box2d(box_a, box_b_corners[k])) {
+ poly_center = poly_center + box_b_corners[k];
+ cross_points[cnt] = box_b_corners[k];
+ cnt++;
+ }
+ if (check_in_box2d(box_b, box_a_corners[k])) {
+ poly_center = poly_center + box_a_corners[k];
+ cross_points[cnt] = box_a_corners[k];
+ cnt++;
+ }
+ }
+
+ poly_center.x /= cnt;
+ poly_center.y /= cnt;
+
+ Point temp;
+ for (int j = 0; j < cnt - 1; j++) {
+ for (int i = 0; i < cnt - j - 1; i++) {
+ if (point_cmp(cross_points[i], cross_points[i + 1], poly_center)) {
+ temp = cross_points[i];
+ cross_points[i] = cross_points[i + 1];
+ cross_points[i + 1] = temp;
+ }
+ }
+ }
+
+ float area = 0.0f;
+ for (int k = 0; k < cnt - 1; k++) {
+ area += cross(cross_points[k] - cross_points[0],
+ cross_points[k + 1] - cross_points[0]);
+ }
+ return std::fabs(area) / 2.0f;
+}
+
+float iou_bev(const float *box_a, const float *box_b) {
+ float sa = (box_a[2] - box_a[0]) * (box_a[3] - box_a[1]);
+ float sb = (box_b[2] - box_b[0]) * (box_b[3] - box_b[1]);
+ float s_overlap = box_overlap(box_a, box_b);
+ return s_overlap / std::fmax(sa + sb - s_overlap, EPS);
+}
diff --git a/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.hpp b/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.hpp
new file mode 100644
index 00000000000..8b4424419e5
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/iou3d_utils.hpp
@@ -0,0 +1,4 @@
+#pragma once
+
+// Forward declarations for IoU 3D utility functions
+float iou_bev(const float* box_a, const float* box_b);
diff --git a/notebooks/3D-point-pillars/ov_extensions/ov_pointpillars_ext.cpp b/notebooks/3D-point-pillars/ov_extensions/ov_pointpillars_ext.cpp
new file mode 100644
index 00000000000..2b8795e5828
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/ov_pointpillars_ext.cpp
@@ -0,0 +1,13 @@
+// OpenVINO Extension library entry point
+// Registers custom operations for PointPillars
+
+#include
+#include
+#include "voxelization_op.hpp"
+#include "postprocessing_op.hpp"
+
+OPENVINO_CREATE_EXTENSIONS(
+ std::vector({
+ std::make_shared>(),
+ std::make_shared>()
+ }));
diff --git a/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.cpp b/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.cpp
new file mode 100644
index 00000000000..f095a3ae4a2
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.cpp
@@ -0,0 +1,416 @@
+#include "postprocessing_op.hpp"
+#include "iou3d_utils.hpp"
+#include
+#include
+#include
+#include
+#include
+
+namespace ov {
+namespace custom_ops {
+
+PostProcessingOp::PostProcessingOp(const ov::Output& bbox_cls_pred,
+ const ov::Output& bbox_pred,
+ const ov::Output& bbox_dir_cls_pred,
+ const std::vector& ranges,
+ const std::vector& sizes,
+ const std::vector& rotations,
+ int nclasses,
+ int nms_pre,
+ float score_thr,
+ float nms_thr,
+ int max_num)
+ : ov::op::Op({bbox_cls_pred, bbox_pred, bbox_dir_cls_pred}),
+ m_ranges(ranges),
+ m_sizes(sizes),
+ m_rotations(rotations),
+ m_nclasses(nclasses),
+ m_nms_pre(nms_pre),
+ m_score_thr(score_thr),
+ m_nms_thr(nms_thr),
+ m_max_num(max_num) {
+ constructor_validate_and_infer_types();
+}
+
+void PostProcessingOp::validate_and_infer_types() {
+ OPENVINO_ASSERT(get_input_size() == 3, "PostProcessingOp expects 3 inputs");
+
+ const auto& cls_shape = get_input_partial_shape(0);
+ const auto& bbox_shape = get_input_partial_shape(1);
+ const auto& dir_shape = get_input_partial_shape(2);
+
+ OPENVINO_ASSERT(cls_shape.rank().is_static() && cls_shape.rank().get_length() == 3,
+ "bbox_cls_pred must be 3D [n_anchors*nclasses, H, W]");
+ OPENVINO_ASSERT(bbox_shape.rank().is_static() && bbox_shape.rank().get_length() == 3,
+ "bbox_pred must be 3D [n_anchors*7, H, W]");
+ OPENVINO_ASSERT(dir_shape.rank().is_static() && dir_shape.rank().get_length() == 3,
+ "bbox_dir_cls_pred must be 3D [n_anchors*2, H, W]");
+
+ // Outputs: bboxes [k, 7], labels [k], scores [k]
+ set_output_type(0, ov::element::f32, ov::PartialShape{ov::Dimension::dynamic(), 7});
+ set_output_type(1, ov::element::i64, ov::PartialShape{ov::Dimension::dynamic()});
+ set_output_type(2, ov::element::f32, ov::PartialShape{ov::Dimension::dynamic()});
+}
+
+std::shared_ptr PostProcessingOp::clone_with_new_inputs(
+ const ov::OutputVector& new_args) const {
+ OPENVINO_ASSERT(new_args.size() == 3, "Incorrect number of new arguments");
+
+ return std::make_shared(new_args[0], new_args[1], new_args[2],
+ m_ranges, m_sizes, m_rotations,
+ m_nclasses, m_nms_pre, m_score_thr, m_nms_thr, m_max_num);
+}
+
+bool PostProcessingOp::visit_attributes(ov::AttributeVisitor& visitor) {
+ visitor.on_attribute("ranges", m_ranges);
+ visitor.on_attribute("sizes", m_sizes);
+ visitor.on_attribute("rotations", m_rotations);
+ visitor.on_attribute("nclasses", m_nclasses);
+ visitor.on_attribute("nms_pre", m_nms_pre);
+ visitor.on_attribute("score_thr", m_score_thr);
+ visitor.on_attribute("nms_thr", m_nms_thr);
+ visitor.on_attribute("max_num", m_max_num);
+ return true;
+}
+
+bool PostProcessingOp::has_evaluate() const {
+ return true;
+}
+
+// Helper: limit_period for angle normalization
+float PostProcessingOp::limit_period(float val, float offset, float period) const {
+ return val - std::floor(val / period + offset) * period;
+}
+
+// Helper: axis-aligned IoU (used in NMS - does NOT consider rotation!)
+inline float iou_normal(const float* a, const float* b) {
+ float left = std::max(a[0], b[0]);
+ float right = std::min(a[2], b[2]);
+ float top = std::max(a[1], b[1]);
+ float bottom = std::min(a[3], b[3]);
+ float width = std::max(right - left, 0.0f);
+ float height = std::max(bottom - top, 0.0f);
+ float interS = width * height;
+ float Sa = (a[2] - a[0]) * (a[3] - a[1]);
+ float Sb = (b[2] - b[0]) * (b[3] - b[1]);
+ return interS / std::max(Sa + Sb - interS, 1e-10f);
+}
+
+// Helper: decode bbox from anchor + delta
+void PostProcessingOp::decode_bbox(const float* anchor, const float* delta, float* bbox) const {
+ // anchor: [x, y, z, w, l, h, theta]
+ // delta: [dx, dy, dz, dw, dl, dh, dtheta]
+ float da = std::sqrt(anchor[3] * anchor[3] + anchor[4] * anchor[4]);
+
+ bbox[0] = delta[0] * da + anchor[0]; // x
+ bbox[1] = delta[1] * da + anchor[1]; // y
+ bbox[2] = delta[2] * anchor[5] + anchor[2] + anchor[5] / 2.0f; // z
+ bbox[3] = anchor[3] * std::exp(delta[3]); // w
+ bbox[4] = anchor[4] * std::exp(delta[4]); // l
+ bbox[5] = anchor[5] * std::exp(delta[5]); // h
+ bbox[2] = bbox[2] - bbox[5] / 2.0f; // z adjustment
+ bbox[6] = anchor[6] + delta[6]; // theta
+}
+
+// Helper: generate anchors for given feature map size
+void PostProcessingOp::generate_anchors(int height, int width, std::vector& anchors) const {
+ // anchors output: [height * width * n_classes * n_rotations, 7]
+ // For PointPillars: 3 classes, 2 rotations → 6 anchors per location
+ // Order: [H, W, 3 classes, 2 rotations, 7]
+ // Flattened as: anchors[(h*W*6 + w*6 + cls*2 + rot) * 7]
+
+ const int n_anchor_classes = m_ranges.size() / 6; // Each class has 6 range values
+ const int n_rotations = m_rotations.size();
+ const int total_anchors = height * width * n_anchor_classes * n_rotations;
+
+ anchors.resize(total_anchors * 7);
+
+ // Loop order: y → x → class → rotation (to match PyTorch [H, W, 3, 2, 7])
+ for (int y = 0; y < height; ++y) {
+ for (int x = 0; x < width; ++x) {
+ for (int cls = 0; cls < n_anchor_classes; ++cls) {
+ const float* range = &m_ranges[cls * 6]; // [x1, y1, z1, x2, y2, z2]
+ const float* size = &m_sizes[cls * 3]; // [w, l, h]
+
+ float x_step = (range[3] - range[0]) / width;
+ float y_step = (range[4] - range[1]) / height;
+ float x_shift = x_step / 2.0f;
+ float y_shift = y_step / 2.0f;
+ float z_center = (range[2] + range[5]) / 2.0f;
+
+ float x_center = range[0] + x * x_step + x_shift;
+ float y_center = range[1] + y * y_step + y_shift;
+
+ for (int rot = 0; rot < n_rotations; ++rot) {
+ // Index: (h * W * 6 + w * 6 + cls * 2 + rot) * 7
+ int anchor_idx = ((y * width + x) * n_anchor_classes + cls) * n_rotations + rot;
+ float* anchor = &anchors[anchor_idx * 7];
+ anchor[0] = x_center;
+ anchor[1] = y_center;
+ anchor[2] = z_center;
+ anchor[3] = size[0]; // w
+ anchor[4] = size[1]; // l
+ anchor[5] = size[2]; // h
+ anchor[6] = m_rotations[rot]; // theta
+ }
+ }
+ }
+ }
+}
+
+bool PostProcessingOp::evaluate(ov::TensorVector& outputs, const ov::TensorVector& inputs) const {
+ OPENVINO_ASSERT(inputs.size() == 3, "PostProcessingOp expects 3 inputs");
+ OPENVINO_ASSERT(outputs.size() == 3, "PostProcessingOp expects 3 outputs");
+
+ const auto& cls_tensor = inputs[0];
+ const auto& bbox_tensor = inputs[1];
+ const auto& dir_tensor = inputs[2];
+
+ const auto cls_shape = cls_tensor.get_shape(); // [n_anchors*nclasses, H, W]
+ const int height = cls_shape[1];
+ const int width = cls_shape[2];
+ const int n_anchor_per_loc = 6; // 3 classes * 2 rotations
+ const int total_anchors = height * width * n_anchor_per_loc;
+
+ const float* cls_data = cls_tensor.data();
+ const float* bbox_data = bbox_tensor.data();
+ const float* dir_data = dir_tensor.data();
+
+ // Step 1: Generate anchors
+ std::vector anchors;
+ // std::cout << "Generating anchors for feature map size: " << height << "x" << width << std::endl;
+ generate_anchors(height, width, anchors);
+
+ // Step 2: Transpose and reshape predictions
+ // cls_pred: [n_anchors*nclasses, H, W] → [H, W, n_anchors*nclasses] → [total_anchors, nclasses]
+ std::vector cls_reshaped(total_anchors * m_nclasses);
+ std::vector bbox_reshaped(total_anchors * 7);
+ std::vector dir_reshaped(total_anchors * 2);
+
+ for (int h = 0; h < height; ++h) {
+ for (int w = 0; w < width; ++w) {
+ for (int a = 0; a < n_anchor_per_loc; ++a) {
+ int out_idx = (h * width + w) * n_anchor_per_loc + a;
+
+ // Classification scores (per class)
+ for (int c = 0; c < m_nclasses; ++c) {
+ int in_idx = ((a * m_nclasses + c) * height + h) * width + w;
+ cls_reshaped[out_idx * m_nclasses + c] = cls_data[in_idx];
+ }
+
+ // BBox deltas
+ for (int d = 0; d < 7; ++d) {
+ int in_idx = ((a * 7 + d) * height + h) * width + w;
+ bbox_reshaped[out_idx * 7 + d] = bbox_data[in_idx];
+ }
+
+ // Direction classification
+ for (int d = 0; d < 2; ++d) {
+ int in_idx = ((a * 2 + d) * height + h) * width + w;
+ dir_reshaped[out_idx * 2 + d] = dir_data[in_idx];
+ }
+ }
+ }
+ }
+
+ // Step 3: Apply sigmoid to classification scores
+ for (size_t i = 0; i < cls_reshaped.size(); ++i) {
+ cls_reshaped[i] = 1.0f / (1.0f + std::exp(-cls_reshaped[i]));
+ }
+
+ // Step 4: Get direction class (argmax)
+ std::vector dir_classes(total_anchors);
+ for (int i = 0; i < total_anchors; ++i) {
+ dir_classes[i] = dir_reshaped[i * 2] > dir_reshaped[i * 2 + 1] ? 0 : 1;
+ }
+
+ // Step 5: Select top nms_pre boxes by max class score
+ std::vector> score_indices;
+ for (int i = 0; i < total_anchors; ++i) {
+ float max_score = 0.0f;
+ for (int c = 0; c < m_nclasses; ++c) {
+ max_score = std::max(max_score, cls_reshaped[i * m_nclasses + c]);
+ }
+ score_indices.push_back({max_score, i});
+ }
+
+ std::partial_sort(score_indices.begin(),
+ score_indices.begin() + std::min(m_nms_pre, (int)score_indices.size()),
+ score_indices.end(),
+ [](const auto& a, const auto& b) { return a.first > b.first; });
+
+ int nms_pre_actual = std::min(m_nms_pre, (int)score_indices.size());
+
+ // Step 6: Decode bboxes for selected indices
+ std::vector decoded_bboxes(nms_pre_actual * 7);
+ std::vector selected_cls_scores(nms_pre_actual * m_nclasses);
+ std::vector selected_dir_classes(nms_pre_actual);
+
+ for (int i = 0; i < nms_pre_actual; ++i) {
+ int idx = score_indices[i].second;
+ decode_bbox(&anchors[idx * 7], &bbox_reshaped[idx * 7], &decoded_bboxes[i * 7]);
+ for (int c = 0; c < m_nclasses; ++c) {
+ selected_cls_scores[i * m_nclasses + c] = cls_reshaped[idx * m_nclasses + c];
+ }
+ selected_dir_classes[i] = dir_classes[idx];
+ }
+
+ // Step 7: Per-class NMS using mask-based algorithm (matching PyTorch exactly)
+ std::vector final_bboxes;
+ std::vector final_labels;
+ std::vector final_scores;
+
+ const int THREADS_PER_BLOCK_NMS = 64; // Similar to PyTorch
+
+ for (int cls = 0; cls < m_nclasses; ++cls) {
+ // Filter by score threshold
+ std::vector cls_indices;
+ std::vector cls_scores;
+
+ for (int i = 0; i < nms_pre_actual; ++i) {
+ float score = selected_cls_scores[i * m_nclasses + cls];
+ if (score > m_score_thr) {
+ cls_indices.push_back(i);
+ cls_scores.push_back(score);
+ }
+ }
+
+ if (cls_indices.empty()) continue;
+
+ int boxes_num = cls_indices.size();
+
+ // Sort by score descending (same as PyTorch)
+ std::vector order(boxes_num);
+ for (int i = 0; i < boxes_num; ++i) order[i] = i;
+ std::sort(order.begin(), order.end(),
+ [&cls_scores](int a, int b) { return cls_scores[a] > cls_scores[b]; });
+
+ // Create sorted arrays of boxes (in 2D format) to match PyTorch's nms_kernel input
+ std::vector sorted_boxes_2d(boxes_num * 5);
+ for (int i = 0; i < boxes_num; ++i) {
+ int orig_idx = cls_indices[order[i]];
+ const float* bbox = &decoded_bboxes[orig_idx * 7];
+ sorted_boxes_2d[i * 5 + 0] = bbox[0] - bbox[3] / 2.0f; // xmin
+ sorted_boxes_2d[i * 5 + 1] = bbox[1] - bbox[4] / 2.0f; // ymin
+ sorted_boxes_2d[i * 5 + 2] = bbox[0] + bbox[3] / 2.0f; // xmax
+ sorted_boxes_2d[i * 5 + 3] = bbox[1] + bbox[4] / 2.0f; // ymax
+ sorted_boxes_2d[i * 5 + 4] = bbox[6]; // theta
+ }
+
+ // Apply mask-based NMS (similar to PyTorch nms_kernel)
+ const int col_blocks = (boxes_num + THREADS_PER_BLOCK_NMS - 1) / THREADS_PER_BLOCK_NMS;
+ std::vector mask(boxes_num * col_blocks, 0);
+
+ // Compute overlap mask
+ for (int row_start = 0; row_start < col_blocks; ++row_start) {
+ for (int col_start = 0; col_start < col_blocks; ++col_start) {
+ int row_size = std::min(boxes_num - row_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+ int col_size = std::min(boxes_num - col_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+
+ for (int t = 0; t < row_size; ++t) {
+ int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + t;
+ const float* cur_box = &sorted_boxes_2d[cur_box_idx * 5];
+ unsigned long long u = 0ULL;
+ int start = (row_start == col_start) ? (t + 1) : 0;
+
+ for (int i = start; i < col_size; ++i) {
+ int other_idx = THREADS_PER_BLOCK_NMS * col_start + i;
+ const float* other = &sorted_boxes_2d[other_idx * 5];
+ if (iou_bev(cur_box, other) > m_nms_thr) {
+ u |= (1ULL << i);
+ }
+ }
+ mask[cur_box_idx * col_blocks + col_start] = u;
+ }
+ }
+ }
+
+ // Extract keep indices from mask (same as PyTorch)
+ std::vector remv(col_blocks, 0);
+ std::vector keep_indices;
+
+ for (int i = 0; i < boxes_num; ++i) {
+ int nblock = i / THREADS_PER_BLOCK_NMS;
+ int inblock = i % THREADS_PER_BLOCK_NMS;
+
+ bool is_removed = (remv[nblock] & (1ULL << inblock)) != 0;
+ // if (cls == 2 && i < 10) {
+ // std::printf("[DEBUG] Box %d: nblock=%d inblock=%d remv[%d]=0x%016llx is_removed=%d\n",
+ // i, nblock, inblock, nblock, remv[nblock], is_removed);
+ // }
+
+ if (!is_removed) {
+ keep_indices.push_back(i); // This is already sorted index
+ unsigned long long* p = &mask[i * col_blocks];
+ for (int j = nblock; j < col_blocks; ++j) {
+ remv[j] |= p[j];
+ }
+ }
+ }
+
+ // Add kept boxes to final results
+ for (int sorted_idx : keep_indices) {
+ int orig_idx = cls_indices[order[sorted_idx]];
+ const float* bbox_i = &decoded_bboxes[orig_idx * 7];
+
+ // Apply direction adjustment
+ float theta = limit_period(bbox_i[6], 1.0f, M_PI);
+ theta += (1 - selected_dir_classes[orig_idx]) * M_PI;
+
+ // Add to results
+ final_bboxes.insert(final_bboxes.end(), bbox_i, bbox_i + 7);
+ final_bboxes.back() = theta; // Update with adjusted theta
+ final_labels.push_back(cls);
+ final_scores.push_back(cls_scores[order[sorted_idx]]);
+ }
+ }
+
+ // Step 8: Apply max_num filtering (limit total detections)
+ if (final_labels.size() > (size_t)m_max_num) {
+ // Sort by score descending and keep top max_num
+ std::vector> score_idx;
+ for (size_t i = 0; i < final_labels.size(); ++i) {
+ score_idx.push_back({final_scores[i], i});
+ }
+ std::partial_sort(score_idx.begin(),
+ score_idx.begin() + m_max_num,
+ score_idx.end(),
+ [](const auto& a, const auto& b) { return a.first > b.first; });
+
+ // Keep only top max_num
+ std::vector filtered_bboxes;
+ std::vector filtered_labels;
+ std::vector filtered_scores;
+
+ for (int i = 0; i < m_max_num; ++i) {
+ int idx = score_idx[i].second;
+ filtered_bboxes.insert(filtered_bboxes.end(),
+ &final_bboxes[idx * 7],
+ &final_bboxes[idx * 7 + 7]);
+ filtered_labels.push_back(final_labels[idx]);
+ filtered_scores.push_back(final_scores[idx]);
+ }
+
+ final_bboxes = filtered_bboxes;
+ final_labels = filtered_labels;
+ final_scores = filtered_scores;
+ }
+
+ // Step 9: Set outputs
+ int num_detections = final_labels.size();
+
+ outputs[0].set_shape({(size_t)num_detections, 7});
+ outputs[1].set_shape({(size_t)num_detections});
+ outputs[2].set_shape({(size_t)num_detections});
+
+ if (num_detections > 0) {
+ std::memcpy(outputs[0].data(), final_bboxes.data(), final_bboxes.size() * sizeof(float));
+ std::memcpy(outputs[1].data(), final_labels.data(), final_labels.size() * sizeof(int64_t));
+ std::memcpy(outputs[2].data(), final_scores.data(), final_scores.size() * sizeof(float));
+ }
+
+ return true;
+}
+
+} // namespace custom_ops
+} // namespace ov
diff --git a/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.hpp b/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.hpp
new file mode 100644
index 00000000000..dd9aae9f8bc
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/postprocessing_op.hpp
@@ -0,0 +1,80 @@
+#pragma once
+
+#include
+
+namespace ov {
+namespace custom_ops {
+
+/**
+ * @brief PostProcessingOp: End-to-end post-processing for PointPillars
+ *
+ * Inputs:
+ * - bbox_cls_pred: [n_anchors*3, H, W] - classification logits
+ * - bbox_pred: [n_anchors*7, H, W] - bbox delta predictions
+ * - bbox_dir_cls_pred: [n_anchors*2, H, W] - direction classification logits
+ *
+ * Outputs:
+ * - bboxes: [k, 7] - predicted bboxes (x, y, z, w, l, h, theta)
+ * - labels: [k] - class labels (int64)
+ * - scores: [k] - confidence scores
+ *
+ * Attributes:
+ * - ranges: [[x1,y1,z1,x2,y2,z2], ...] for each class (flattened array)
+ * - sizes: [[w,l,h], ...] for each class (flattened array)
+ * - rotations: [0, 1.57] rotation angles
+ * - nclasses: number of classes (3 for Car, Pedestrian, Cyclist)
+ * - nms_pre: number of top boxes to keep before NMS
+ * - score_thr: score threshold for filtering
+ * - nms_thr: IoU threshold for NMS
+ */
+class PostProcessingOp : public ov::op::Op {
+public:
+ OPENVINO_OP("PostProcessingOp", "custom_ops");
+
+ PostProcessingOp() = default;
+
+ PostProcessingOp(const ov::Output& bbox_cls_pred,
+ const ov::Output& bbox_pred,
+ const ov::Output& bbox_dir_cls_pred,
+ const std::vector& ranges,
+ const std::vector& sizes,
+ const std::vector& rotations,
+ int nclasses,
+ int nms_pre,
+ float score_thr,
+ float nms_thr,
+ int max_num);
+
+ void validate_and_infer_types() override;
+
+ std::shared_ptr clone_with_new_inputs(
+ const ov::OutputVector& new_args) const override;
+
+ bool visit_attributes(ov::AttributeVisitor& visitor) override;
+
+ bool has_evaluate() const override;
+
+ bool evaluate(ov::TensorVector& outputs,
+ const ov::TensorVector& inputs) const override;
+
+private:
+ // Anchor configuration
+ std::vector m_ranges; // Flattened: 3 classes * 6 values
+ std::vector m_sizes; // Flattened: 3 classes * 3 values
+ std::vector m_rotations; // [0, 1.57]
+
+ // Post-processing parameters
+ int m_nclasses;
+ int m_nms_pre;
+ float m_score_thr;
+ float m_nms_thr;
+ int m_max_num;
+
+ // Helper functions
+ void generate_anchors(int height, int width, std::vector& anchors) const;
+ void decode_bbox(const float* anchor, const float* delta, float* bbox) const;
+ float limit_period(float val, float offset, float period) const;
+};
+
+} // namespace custom_ops
+} // namespace ov
diff --git a/notebooks/3D-point-pillars/ov_extensions/voxelization_op.cpp b/notebooks/3D-point-pillars/ov_extensions/voxelization_op.cpp
new file mode 100644
index 00000000000..d1d2ced68f0
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/voxelization_op.cpp
@@ -0,0 +1,197 @@
+// OpenVINO custom operation for PointPillars voxelization
+
+#include "voxelization_op.hpp"
+#include
+#include
+#include
+#include
+#include
+
+namespace ov {
+namespace custom_ops {
+
+VoxelizationOp::VoxelizationOp(const ov::Output& points,
+ const std::vector& voxel_size,
+ const std::vector& point_cloud_range,
+ int max_points_per_voxel,
+ int max_voxels)
+ : ov::op::Op({points}),
+ m_voxel_size(voxel_size),
+ m_point_cloud_range(point_cloud_range),
+ m_max_points_per_voxel(max_points_per_voxel),
+ m_max_voxels(max_voxels) {
+ constructor_validate_and_infer_types();
+}
+
+void VoxelizationOp::validate_and_infer_types() {
+ OPENVINO_ASSERT(get_input_size() == 1, "VoxelizationOp expects 1 input");
+
+ const auto& points_shape = get_input_partial_shape(0);
+ OPENVINO_ASSERT(points_shape.rank().is_static() && points_shape.rank().get_length() == 2,
+ "Points input must be 2D [num_points, num_features]");
+
+ // Output shapes:
+ // voxels: [-1, max_points_per_voxel, num_features] (dynamic voxel count)
+ // coors: [-1, 4] (batch_idx, x, y, z indices)
+ // num_points_per_voxel: [-1]
+
+ const auto num_features = points_shape[1];
+
+ set_output_type(0, get_input_element_type(0),
+ ov::PartialShape{ov::Dimension::dynamic(),
+ m_max_points_per_voxel, num_features});
+ set_output_type(1, ov::element::i64,
+ ov::PartialShape{ov::Dimension::dynamic(), 4});
+ set_output_type(2, ov::element::i64,
+ ov::PartialShape{ov::Dimension::dynamic()});
+}
+
+std::shared_ptr VoxelizationOp::clone_with_new_inputs(
+ const ov::OutputVector& new_args) const {
+ OPENVINO_ASSERT(new_args.size() == 1, "Incorrect number of new arguments");
+
+ return std::make_shared(new_args[0],
+ m_voxel_size,
+ m_point_cloud_range,
+ m_max_points_per_voxel,
+ m_max_voxels);
+}
+
+bool VoxelizationOp::visit_attributes(ov::AttributeVisitor& visitor) {
+ visitor.on_attribute("voxel_size", m_voxel_size);
+ visitor.on_attribute("point_cloud_range", m_point_cloud_range);
+ visitor.on_attribute("max_points_per_voxel", m_max_points_per_voxel);
+ visitor.on_attribute("max_voxels", m_max_voxels);
+ return true;
+}
+
+bool VoxelizationOp::has_evaluate() const {
+ return true;
+}
+
+bool VoxelizationOp::evaluate(ov::TensorVector& outputs, const ov::TensorVector& inputs) const {
+ OPENVINO_ASSERT(inputs.size() == 1, "VoxelizationOp expects 1 input");
+ OPENVINO_ASSERT(outputs.size() == 3, "VoxelizationOp expects 3 outputs");
+
+ const auto& points_tensor = inputs[0];
+ const auto points_shape = points_tensor.get_shape();
+ const int num_points = points_shape[0];
+ const int num_features = points_shape[1];
+
+ const float* points_data = points_tensor.data();
+
+ // Prepare outputs - use temporary buffers with max size
+ auto& voxels_tensor = outputs[0];
+ auto& coors_tensor = outputs[1];
+ auto& num_points_tensor = outputs[2];
+
+ // Allocate temporary buffers with max_voxels size
+ std::vector voxels_buf(
+ m_max_voxels * m_max_points_per_voxel * num_features, 0.0f);
+ std::vector coors_buf(m_max_voxels * 4,
+ 0); // 4 columns: batch_idx, x, y, z
+ std::vector num_points_buf(m_max_voxels, 0);
+
+ float *voxels_data = voxels_buf.data();
+ int64_t *coors_data = coors_buf.data();
+ int64_t *num_points_data = num_points_buf.data();
+
+ // Grid dimensions
+ const float vx = m_voxel_size[0];
+ const float vy = m_voxel_size[1];
+ const float vz = m_voxel_size[2];
+
+ const float x_min = m_point_cloud_range[0];
+ const float y_min = m_point_cloud_range[1];
+ const float z_min = m_point_cloud_range[2];
+ const float x_max = m_point_cloud_range[3];
+ const float y_max = m_point_cloud_range[4];
+ const float z_max = m_point_cloud_range[5];
+
+ const int grid_x = std::round((x_max - x_min) / vx);
+ const int grid_y = std::round((y_max - y_min) / vy);
+ const int grid_z = std::round((z_max - z_min) / vz);
+
+ // Hash map to track voxel indices
+ std::unordered_map coor_to_voxelidx;
+ int voxel_num = 0;
+
+ for (int i = 0; i < num_points; ++i) {
+ const float* point = points_data + i * num_features;
+ const float px = point[0];
+ const float py = point[1];
+ const float pz = point[2];
+
+ // Check if point is in range
+ if (px < x_min || px >= x_max || py < y_min || py >= y_max ||
+ pz < z_min || pz >= z_max) {
+ continue;
+ }
+
+ // Compute voxel coordinates
+ int c_x = std::floor((px - x_min) / vx);
+ int c_y = std::floor((py - y_min) / vy);
+ int c_z = std::floor((pz - z_min) / vz);
+
+ // Clamp to grid
+ c_x = std::max(0, std::min(c_x, grid_x - 1));
+ c_y = std::max(0, std::min(c_y, grid_y - 1));
+ c_z = std::max(0, std::min(c_z, grid_z - 1));
+
+ // Compute hash (linearize coordinates)
+ int coor_hash = c_z * grid_y * grid_x + c_y * grid_x + c_x;
+
+ int voxel_idx;
+ auto it = coor_to_voxelidx.find(coor_hash);
+ if (it == coor_to_voxelidx.end()) {
+ // New voxel
+ if (voxel_num >= m_max_voxels) {
+ continue; // Max voxels reached
+ }
+ voxel_idx = voxel_num;
+ coor_to_voxelidx[coor_hash] = voxel_idx;
+
+ coors_data[voxel_idx * 4 + 0] =
+ 0; // batch index (always 0 for single sample)
+ coors_data[voxel_idx * 4 + 1] = c_x;
+ coors_data[voxel_idx * 4 + 2] = c_y;
+ coors_data[voxel_idx * 4 + 3] = c_z;
+
+ voxel_num++;
+ } else {
+ voxel_idx = it->second;
+ }
+
+ // Add point to voxel
+ int64_t& num_pts = num_points_data[voxel_idx];
+ if (num_pts < m_max_points_per_voxel) {
+ float* voxel_point = voxels_data +
+ (voxel_idx * m_max_points_per_voxel + num_pts) * num_features;
+ std::memcpy(voxel_point, point, num_features * sizeof(float));
+ num_pts++;
+ }
+ }
+
+ // std::cerr << "[VoxelizationOp] voxel_num=" << voxel_num
+ // << ", m_max_voxels=" << m_max_voxels << std::endl;
+
+ voxels_tensor.set_shape({static_cast(voxel_num),
+ static_cast(m_max_points_per_voxel),
+ static_cast(num_features)});
+ coors_tensor.set_shape({static_cast(voxel_num), 4});
+ num_points_tensor.set_shape({static_cast(voxel_num)});
+
+ // Copy only the valid voxel data to output tensors
+ std::memcpy(voxels_tensor.data(), voxels_buf.data(),
+ voxel_num * m_max_points_per_voxel * num_features *
+ sizeof(float));
+ std::memcpy(coors_tensor.data(), coors_buf.data(),
+ voxel_num * 4 * sizeof(int64_t));
+ std::memcpy(num_points_tensor.data(), num_points_buf.data(),
+ voxel_num * sizeof(int64_t));
+
+ return true;
+}
+
+} // namespace custom_ops
+} // namespace ov
diff --git a/notebooks/3D-point-pillars/ov_extensions/voxelization_op.hpp b/notebooks/3D-point-pillars/ov_extensions/voxelization_op.hpp
new file mode 100644
index 00000000000..1d23dd70f01
--- /dev/null
+++ b/notebooks/3D-point-pillars/ov_extensions/voxelization_op.hpp
@@ -0,0 +1,39 @@
+// OpenVINO custom operation for PointPillars voxelization
+
+#pragma once
+#include
+
+namespace ov {
+namespace custom_ops {
+
+class VoxelizationOp : public ov::op::Op {
+public:
+ OPENVINO_OP("VoxelizationOp");
+
+ VoxelizationOp() = default;
+
+ VoxelizationOp(const ov::Output& points,
+ const std::vector& voxel_size,
+ const std::vector& point_cloud_range,
+ int max_points_per_voxel,
+ int max_voxels);
+
+ void validate_and_infer_types() override;
+
+ std::shared_ptr clone_with_new_inputs(const ov::OutputVector& new_args) const override;
+
+ bool visit_attributes(ov::AttributeVisitor& visitor) override;
+
+ bool evaluate(ov::TensorVector& outputs, const ov::TensorVector& inputs) const override;
+
+ bool has_evaluate() const override;
+
+private:
+ std::vector m_voxel_size; // [vx, vy, vz]
+ std::vector m_point_cloud_range; // [x_min, y_min, z_min, x_max, y_max, z_max]
+ int m_max_points_per_voxel;
+ int m_max_voxels;
+};
+
+} // namespace custom_ops
+} // namespace ov
diff --git a/notebooks/3D-point-pillars/pointpillars.ipynb b/notebooks/3D-point-pillars/pointpillars.ipynb
new file mode 100644
index 00000000000..b47badfa021
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars.ipynb
@@ -0,0 +1,415 @@
+{
+ "cells": [
+ {
+ "cell_type": "markdown",
+ "id": "892bd49e",
+ "metadata": {},
+ "source": [
+ "# **PointPillar for 3D object detection**\n",
+ "\n",
+ "PointPillar is a fast and efficient deep-learning architecture for 3D object detection from LiDAR point clouds, commonly used in autonomous driving.\n",
+ "\n",
+ "Instead of operating directly on raw points or dense 3D voxels, PointPillar groups points into vertical columns (\"pillars\") and encodes per-pillar features. These pillar features are arranged into a pseudo-image that a 2D convolutional backbone can process. The pipeline is lightweight and well-suited for real-time inference.\n",
+ "\n",
+ "Core stages:\n",
+ "- Voxelization / Pillarization: group points into pillars and compute per-pillar statistics.\n",
+ "- Pillar feature encoding: a small network encodes points in each pillar into a fixed-size feature vector.\n",
+ "- Scatter to pseudo-image: place each pillar's feature into a 2D grid (pseudo-image) based on the pillar's XY location.\n",
+ "- 2D backbone + neck: apply 2D convolutions to produce multi-scale feature maps.\n",
+ "- Detection head: predict class scores, bounding box regressions, and directions on the pseudo-image.\n",
+ "- Post-processing: decode boxes, apply non-maximum suppression (NMS), and output final detections."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "a84ce99b",
+ "metadata": {},
+ "source": [
+ "#### **Table of contents:**\n",
+ "1. [Prerequisites](#prerequisites)\n",
+ "2. [Install python packages](#install-python-packages)\n",
+ "3. [Build Extensions](#build-extensions)\n",
+ "4. [Exporting the model](#exporting-the-model)\n",
+ "5. [Inference with OpenVINO](#inference-with-openvino)\n",
+ "6. Utilities\n",
+ " * [Kitti bin to pcd](#kitti-bin-to-pcd)\n",
+ " * [Running benchmark_app](#running-benchmark_app)\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "7a56c177",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Prerequisites:**\n",
+ "\n",
+ "\n",
+ "```bash\n",
+ "# Install the required packages specific to this notebook.\n",
+ "sudo apt update && sudo apt install -y \\\n",
+ " software-properties-common \\\n",
+ " build-essential \\\n",
+ " cmake \\\n",
+ " git \\\n",
+ " libx11-6 \\\n",
+ " libgl1\n",
+ "\n",
+ "# Install Intel GPU runtime for OpenCL\n",
+ "sudo add-apt-repository -y ppa:kobuk-team/intel-graphics\n",
+ "sudo apt update\n",
+ "sudo apt install -y --no-install-recommends \\\n",
+ " libze-intel-gpu1 \\\n",
+ " intel-opencl-icd\n",
+ "\n",
+ "# Create a python 3.10 environment, conda can be used to manage environments:\n",
+ "conda install python=3.10\n",
+ "conda create -n ovpp310 python=3.10\n",
+ "conda activate ovpp310\n",
+ "# conda deactivate\n",
+ "# conda env remove -n ovpp310\n",
+ "```\n",
+ "\n",
+ "**Python 3.10** is recommended to run this notebook. We also recommend running the notebook in a _virtual environment_. You only need a Jupyter server to start. For details, please refer to [Installation Guide](https://github.com/openvinotoolkit/openvino_notebooks/blob/latest/README.md#-installation-guide)."
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "07229d50",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Install python packages:**"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "30321310",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "echo \"SCRIPT_DIR: ${SCRIPT_DIR}\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# Install the required pip packages specific to this notebook\n",
+ "python -m pip install -r requirements.txt\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "8ac1f4b8",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Build Extensions:**"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "da3d47ff",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "echo \"SCRIPT_DIR: ${SCRIPT_DIR}\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# Build the openvino extension\n",
+ "cd \"${SCRIPT_DIR}/ov_extensions\" && rm -rf build/ && bash build.sh && cd ..\n",
+ "\n",
+ "# Build the pytorch extensions (will be used only to export the model)\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "CPU_BUILD=1 python setup.py build_ext --inplace\n",
+ "cd ..\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "f41acf68",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "\n",
+ "
\n",
+ "\n",
+ "#### **Exporting the model:**\n",
+ "\n",
+ "In the model declaration, we can see it has five layers. Out of these five layers, the first layer is the Pillar Layer where a pytorch extension (voxelization) is used. For exporting the model to OpenVINO format, we skip this layer and export the remaining layers to OpenVINO format. During inference, we run the Pillar Layer separately using the openvino extension and then pass the output to the OpenVINO model for further processing.\n",
+ "\n",
+ "```python\n",
+ "class NeuralNetworkPortion(nn.Module):\n",
+ " \"\"\"Neural network portion: PillarEncoder + Backbone + Neck + Head\"\"\"\n",
+ "\n",
+ " def __init__(self, model):\n",
+ " super().__init__()\n",
+ " self.pillar_encoder = model.pillar_encoder\n",
+ " self.backbone = model.backbone\n",
+ " self.neck = model.neck\n",
+ " self.head = model.head\n",
+ "\n",
+ " def forward(self, pillars, coors, npoints):\n",
+ " pillar_features = self.pillar_encoder(pillars, coors, npoints)\n",
+ " xs = self.backbone(pillar_features)\n",
+ " x = self.neck(xs)\n",
+ " cls_preds, box_preds, dir_cls_preds = self.head(x)\n",
+ " return cls_preds, box_preds, dir_cls_preds\n",
+ "```\n",
+ "\n",
+ "Getting the neural network portion of the PointPillars model:\n",
+ "\n",
+ "```python\n",
+ "full_model = PointPillars()\n",
+ "checkpoint = torch.load(checkpoint_path, map_location='cpu', weights_only=False)\n",
+ "full_model.load_state_dict(checkpoint)\n",
+ "full_model.eval()\n",
+ "\n",
+ "nn_portion = NeuralNetworkPortion(full_model)\n",
+ "```\n",
+ "\n",
+ "Then defining dummy inputs for the model to export:\n",
+ "\n",
+ "```python\n",
+ "dummy_pillars = torch.randn(max_voxels, max_points, 4)\n",
+ "dummy_npoints = torch.randint(1, max_points, (max_voxels,)).long()\n",
+ "\n",
+ "vx, vy, vz = voxel_size[0], voxel_size[1], voxel_size[2]\n",
+ "x_l = int((point_cloud_range[3] - point_cloud_range[0]) / vx)\n",
+ "y_l = int((point_cloud_range[4] - point_cloud_range[1]) / vy)\n",
+ "z_l = int((point_cloud_range[5] - point_cloud_range[2]) / vz)\n",
+ "dummy_coors = torch.empty((max_voxels, 4), dtype=torch.long)\n",
+ "dummy_coors[:, 0] = 0 # batch index\n",
+ "if z_l > 0:\n",
+ " dummy_coors[:, 1] = torch.randint(0, z_l, (max_voxels,))\n",
+ "else:\n",
+ " dummy_coors[:, 1] = 0\n",
+ "dummy_coors[:, 2] = torch.randint(0, y_l, (max_voxels,))\n",
+ "dummy_coors[:, 3] = torch.randint(0, x_l, (max_voxels,))\n",
+ "```\n",
+ "\n",
+ "Finally, exporting the model to OpenVINO format:\n",
+ "\n",
+ "```python\n",
+ "with torch.no_grad():\n",
+ " traced_nn = torch.jit.trace(\n",
+ " nn_portion,\n",
+ " (dummy_pillars, dummy_coors, dummy_npoints),\n",
+ " check_trace=False,\n",
+ " strict=False\n",
+ " )\n",
+ " ov_nn_model = ov.convert_model(\n",
+ " traced_nn,\n",
+ " example_input=(dummy_pillars, dummy_coors, dummy_npoints),\n",
+ " input=[\n",
+ " ov.PartialShape([-1, max_points, 4]), # pillars\n",
+ " ov.PartialShape([-1, 4]), # coors\n",
+ " ov.PartialShape([-1]), # npoints\n",
+ " ]\n",
+ " )\n",
+ "```\n",
+ "\n",
+ "And saving the neural network model:\n",
+ "\n",
+ "```python\n",
+ "ov.save_model(ov_nn_model, nn_xml_path)\n",
+ "```\n",
+ "\n",
+ "The other preprocessing and post-processing steps (including voxelization, non-maximum suppression, etc.) are handled separately using OpenVINO custom extensions. The details of the xml and other parameters are implemented in `create_pillar_layer_ir` and `create_postprocessing_ir` functions available in `export_ov_e2e.py`. \n"
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "81b436e5",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# Export the PointPillars model to OpenVINO format\n",
+ "python export_ov_e2e.py --checkpoint \"${SCRIPT_DIR}/pretrained/epoch_160.pth\" --output \"${SCRIPT_DIR}/pretrained/pointpillars_ov\"\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "27b97dcf",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Inference with OpenVINO:**\n",
+ "\n",
+ "For inference, implemented in `e2eOVInference.py`, first voxelizing the raw point cloud with a custom OpenVINO voxelization op, then running the compiled neural network IR on the resulting pillars/coors/npoints, and finally applying a custom OpenVINO post-processing op to decode boxes, apply NMS and output final bboxes, labels and scores.\n",
+ "\n",
+ "**Setup (`__init__`):**\n",
+ "\n",
+ "Load the JSON config produced by export_ov_e2e.py (paths to IRs and extension library) and create an OpenVINO Core instance.\n",
+ "Load the custom extension library and compile three models: voxelization (CPU), neural network (device, e.g. CPU/GPU), and post-processing (CPU).\n",
+ "\n",
+ "**Step 1 — Voxelization (custom OpenVINO op):**\n",
+ "\n",
+ "Call compiled voxel model with the raw points, a filtered point cloud as an N×4 float array (x, y, z, intensity).\n",
+ "Output: pillars (float tensor, each row holds the point for one pillar, zero‑padded to max_points), coors (int tensor, grid coordinates for each pillar), npoints (int tensor, number of valid points in each corresponding pillar).\n",
+ "\n",
+ "**Step 2 — Neural network inference:**\n",
+ "\n",
+ "Feed pillars, coors, npoints into the compiled NN IR.\n",
+ "Output: cls_preds, box_preds, dir_cls_preds (network predictions).\n",
+ "\n",
+ "**Step 3 — Post-processing (custom OpenVINO op):**\n",
+ "\n",
+ "Call compiled postproc model with the network outputs.\n",
+ "Output: final bboxes, labels, and scores (already decoded, NMS applied, rotated IoU handled by the custom op).\n",
+ "Post-processing parameters (anchors, nms thresholds, etc.) come from the config exported earlier."
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "4014604c",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# Run inference with OpenVINO\n",
+ "python e2eOVInference.py --config \"${SCRIPT_DIR}/pretrained/pointpillars_ov_config.json\" --pc_path \"${SCRIPT_DIR}/pointpillars/dataset/demo_data/test/000002.bin\"\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "2b4643da",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Kitti bin to pcd:**\n",
+ "\n",
+ "To convert KITTI dataset files to PCD format, python scripts are provided in the `utils` folder of the PointPillars repository. Below are example commands to convert a single `.bin` file and an entire KITTI split to PCD format."
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "e85b4558",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# Convert single KITTI .bin file to .pcd\n",
+ "python pointpillars/utils/convert_bin_to_pcd.py \"pointpillars/dataset/demo_data/test/000002.bin\" --overwrite --verify\n",
+ "\n",
+ "# Convert entire KITTI val split to .pcd files\n",
+ "# python pointpillars/utils/convert_kitti_split_to_pcd.py --data-root --split val --overwrite --verify\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "d54d54e4",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)\n",
+ "\n",
+ "#### **Running benchmark_app:**\n",
+ "A benchmarking script is provided to measure the performance of the PointPillars model using OpenVINO's `benchmark_app`. You can run the script with different configurations to evaluate various components of the model."
+ ]
+ },
+ {
+ "cell_type": "code",
+ "execution_count": null,
+ "id": "3519d278",
+ "metadata": {
+ "vscode": {
+ "languageId": "shellscript"
+ }
+ },
+ "outputs": [],
+ "source": [
+ "%%bash\n",
+ "SCRIPT_DIR=\"$(cd \"$(dirname \"${BASH_SOURCE[0]}\")\" >/dev/null 2>&1 && pwd)\"\n",
+ "cd \"${SCRIPT_DIR}\"\n",
+ "\n",
+ "# To use `benchmark_app` for performance measurements of the neural network, run:\n",
+ "# ./benchmark-e2eOV.sh [CONFIG] [DEVICE: CPU|GPU] [NITER] [NIREQ] [NSTREAMS] [MODE: all|voxel|nn|postproc]\n",
+ "\n",
+ "# Example, for nn:\n",
+ "\"${SCRIPT_DIR}/benchmark-e2eOV.sh\" \"${SCRIPT_DIR}/pretrained/pointpillars_ov_config.json\" CPU 1000 1 1 nn\n",
+ "\n",
+ "# Example, for all:\n",
+ "\"${SCRIPT_DIR}/benchmark-e2eOV.sh\" \"${SCRIPT_DIR}/pretrained/pointpillars_ov_config.json\" CPU 1000 1 1 all\n"
+ ]
+ },
+ {
+ "cell_type": "markdown",
+ "id": "acb18900",
+ "metadata": {},
+ "source": [
+ "[back to top ⬆️](#Table-of-contents:)"
+ ]
+ }
+ ],
+ "metadata": {
+ "kernelspec": {
+ "display_name": "ovpp311",
+ "language": "python",
+ "name": "python3"
+ },
+ "language_info": {
+ "codemirror_mode": {
+ "name": "ipython",
+ "version": 3
+ },
+ "file_extension": ".py",
+ "mimetype": "text/x-python",
+ "name": "python",
+ "nbconvert_exporter": "python",
+ "pygments_lexer": "ipython3",
+ "version": "3.11.14"
+ }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 5
+}
diff --git a/notebooks/3D-point-pillars/pointpillars/__init__.py b/notebooks/3D-point-pillars/pointpillars/__init__.py
new file mode 100644
index 00000000000..e69de29bb2d
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/test.txt b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/test.txt
new file mode 100644
index 00000000000..5d390023073
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/test.txt
@@ -0,0 +1,7518 @@
+000000
+000001
+000002
+000003
+000004
+000005
+000006
+000007
+000008
+000009
+000010
+000011
+000012
+000013
+000014
+000015
+000016
+000017
+000018
+000019
+000020
+000021
+000022
+000023
+000024
+000025
+000026
+000027
+000028
+000029
+000030
+000031
+000032
+000033
+000034
+000035
+000036
+000037
+000038
+000039
+000040
+000041
+000042
+000043
+000044
+000045
+000046
+000047
+000048
+000049
+000050
+000051
+000052
+000053
+000054
+000055
+000056
+000057
+000058
+000059
+000060
+000061
+000062
+000063
+000064
+000065
+000066
+000067
+000068
+000069
+000070
+000071
+000072
+000073
+000074
+000075
+000076
+000077
+000078
+000079
+000080
+000081
+000082
+000083
+000084
+000085
+000086
+000087
+000088
+000089
+000090
+000091
+000092
+000093
+000094
+000095
+000096
+000097
+000098
+000099
+000100
+000101
+000102
+000103
+000104
+000105
+000106
+000107
+000108
+000109
+000110
+000111
+000112
+000113
+000114
+000115
+000116
+000117
+000118
+000119
+000120
+000121
+000122
+000123
+000124
+000125
+000126
+000127
+000128
+000129
+000130
+000131
+000132
+000133
+000134
+000135
+000136
+000137
+000138
+000139
+000140
+000141
+000142
+000143
+000144
+000145
+000146
+000147
+000148
+000149
+000150
+000151
+000152
+000153
+000154
+000155
+000156
+000157
+000158
+000159
+000160
+000161
+000162
+000163
+000164
+000165
+000166
+000167
+000168
+000169
+000170
+000171
+000172
+000173
+000174
+000175
+000176
+000177
+000178
+000179
+000180
+000181
+000182
+000183
+000184
+000185
+000186
+000187
+000188
+000189
+000190
+000191
+000192
+000193
+000194
+000195
+000196
+000197
+000198
+000199
+000200
+000201
+000202
+000203
+000204
+000205
+000206
+000207
+000208
+000209
+000210
+000211
+000212
+000213
+000214
+000215
+000216
+000217
+000218
+000219
+000220
+000221
+000222
+000223
+000224
+000225
+000226
+000227
+000228
+000229
+000230
+000231
+000232
+000233
+000234
+000235
+000236
+000237
+000238
+000239
+000240
+000241
+000242
+000243
+000244
+000245
+000246
+000247
+000248
+000249
+000250
+000251
+000252
+000253
+000254
+000255
+000256
+000257
+000258
+000259
+000260
+000261
+000262
+000263
+000264
+000265
+000266
+000267
+000268
+000269
+000270
+000271
+000272
+000273
+000274
+000275
+000276
+000277
+000278
+000279
+000280
+000281
+000282
+000283
+000284
+000285
+000286
+000287
+000288
+000289
+000290
+000291
+000292
+000293
+000294
+000295
+000296
+000297
+000298
+000299
+000300
+000301
+000302
+000303
+000304
+000305
+000306
+000307
+000308
+000309
+000310
+000311
+000312
+000313
+000314
+000315
+000316
+000317
+000318
+000319
+000320
+000321
+000322
+000323
+000324
+000325
+000326
+000327
+000328
+000329
+000330
+000331
+000332
+000333
+000334
+000335
+000336
+000337
+000338
+000339
+000340
+000341
+000342
+000343
+000344
+000345
+000346
+000347
+000348
+000349
+000350
+000351
+000352
+000353
+000354
+000355
+000356
+000357
+000358
+000359
+000360
+000361
+000362
+000363
+000364
+000365
+000366
+000367
+000368
+000369
+000370
+000371
+000372
+000373
+000374
+000375
+000376
+000377
+000378
+000379
+000380
+000381
+000382
+000383
+000384
+000385
+000386
+000387
+000388
+000389
+000390
+000391
+000392
+000393
+000394
+000395
+000396
+000397
+000398
+000399
+000400
+000401
+000402
+000403
+000404
+000405
+000406
+000407
+000408
+000409
+000410
+000411
+000412
+000413
+000414
+000415
+000416
+000417
+000418
+000419
+000420
+000421
+000422
+000423
+000424
+000425
+000426
+000427
+000428
+000429
+000430
+000431
+000432
+000433
+000434
+000435
+000436
+000437
+000438
+000439
+000440
+000441
+000442
+000443
+000444
+000445
+000446
+000447
+000448
+000449
+000450
+000451
+000452
+000453
+000454
+000455
+000456
+000457
+000458
+000459
+000460
+000461
+000462
+000463
+000464
+000465
+000466
+000467
+000468
+000469
+000470
+000471
+000472
+000473
+000474
+000475
+000476
+000477
+000478
+000479
+000480
+000481
+000482
+000483
+000484
+000485
+000486
+000487
+000488
+000489
+000490
+000491
+000492
+000493
+000494
+000495
+000496
+000497
+000498
+000499
+000500
+000501
+000502
+000503
+000504
+000505
+000506
+000507
+000508
+000509
+000510
+000511
+000512
+000513
+000514
+000515
+000516
+000517
+000518
+000519
+000520
+000521
+000522
+000523
+000524
+000525
+000526
+000527
+000528
+000529
+000530
+000531
+000532
+000533
+000534
+000535
+000536
+000537
+000538
+000539
+000540
+000541
+000542
+000543
+000544
+000545
+000546
+000547
+000548
+000549
+000550
+000551
+000552
+000553
+000554
+000555
+000556
+000557
+000558
+000559
+000560
+000561
+000562
+000563
+000564
+000565
+000566
+000567
+000568
+000569
+000570
+000571
+000572
+000573
+000574
+000575
+000576
+000577
+000578
+000579
+000580
+000581
+000582
+000583
+000584
+000585
+000586
+000587
+000588
+000589
+000590
+000591
+000592
+000593
+000594
+000595
+000596
+000597
+000598
+000599
+000600
+000601
+000602
+000603
+000604
+000605
+000606
+000607
+000608
+000609
+000610
+000611
+000612
+000613
+000614
+000615
+000616
+000617
+000618
+000619
+000620
+000621
+000622
+000623
+000624
+000625
+000626
+000627
+000628
+000629
+000630
+000631
+000632
+000633
+000634
+000635
+000636
+000637
+000638
+000639
+000640
+000641
+000642
+000643
+000644
+000645
+000646
+000647
+000648
+000649
+000650
+000651
+000652
+000653
+000654
+000655
+000656
+000657
+000658
+000659
+000660
+000661
+000662
+000663
+000664
+000665
+000666
+000667
+000668
+000669
+000670
+000671
+000672
+000673
+000674
+000675
+000676
+000677
+000678
+000679
+000680
+000681
+000682
+000683
+000684
+000685
+000686
+000687
+000688
+000689
+000690
+000691
+000692
+000693
+000694
+000695
+000696
+000697
+000698
+000699
+000700
+000701
+000702
+000703
+000704
+000705
+000706
+000707
+000708
+000709
+000710
+000711
+000712
+000713
+000714
+000715
+000716
+000717
+000718
+000719
+000720
+000721
+000722
+000723
+000724
+000725
+000726
+000727
+000728
+000729
+000730
+000731
+000732
+000733
+000734
+000735
+000736
+000737
+000738
+000739
+000740
+000741
+000742
+000743
+000744
+000745
+000746
+000747
+000748
+000749
+000750
+000751
+000752
+000753
+000754
+000755
+000756
+000757
+000758
+000759
+000760
+000761
+000762
+000763
+000764
+000765
+000766
+000767
+000768
+000769
+000770
+000771
+000772
+000773
+000774
+000775
+000776
+000777
+000778
+000779
+000780
+000781
+000782
+000783
+000784
+000785
+000786
+000787
+000788
+000789
+000790
+000791
+000792
+000793
+000794
+000795
+000796
+000797
+000798
+000799
+000800
+000801
+000802
+000803
+000804
+000805
+000806
+000807
+000808
+000809
+000810
+000811
+000812
+000813
+000814
+000815
+000816
+000817
+000818
+000819
+000820
+000821
+000822
+000823
+000824
+000825
+000826
+000827
+000828
+000829
+000830
+000831
+000832
+000833
+000834
+000835
+000836
+000837
+000838
+000839
+000840
+000841
+000842
+000843
+000844
+000845
+000846
+000847
+000848
+000849
+000850
+000851
+000852
+000853
+000854
+000855
+000856
+000857
+000858
+000859
+000860
+000861
+000862
+000863
+000864
+000865
+000866
+000867
+000868
+000869
+000870
+000871
+000872
+000873
+000874
+000875
+000876
+000877
+000878
+000879
+000880
+000881
+000882
+000883
+000884
+000885
+000886
+000887
+000888
+000889
+000890
+000891
+000892
+000893
+000894
+000895
+000896
+000897
+000898
+000899
+000900
+000901
+000902
+000903
+000904
+000905
+000906
+000907
+000908
+000909
+000910
+000911
+000912
+000913
+000914
+000915
+000916
+000917
+000918
+000919
+000920
+000921
+000922
+000923
+000924
+000925
+000926
+000927
+000928
+000929
+000930
+000931
+000932
+000933
+000934
+000935
+000936
+000937
+000938
+000939
+000940
+000941
+000942
+000943
+000944
+000945
+000946
+000947
+000948
+000949
+000950
+000951
+000952
+000953
+000954
+000955
+000956
+000957
+000958
+000959
+000960
+000961
+000962
+000963
+000964
+000965
+000966
+000967
+000968
+000969
+000970
+000971
+000972
+000973
+000974
+000975
+000976
+000977
+000978
+000979
+000980
+000981
+000982
+000983
+000984
+000985
+000986
+000987
+000988
+000989
+000990
+000991
+000992
+000993
+000994
+000995
+000996
+000997
+000998
+000999
+001000
+001001
+001002
+001003
+001004
+001005
+001006
+001007
+001008
+001009
+001010
+001011
+001012
+001013
+001014
+001015
+001016
+001017
+001018
+001019
+001020
+001021
+001022
+001023
+001024
+001025
+001026
+001027
+001028
+001029
+001030
+001031
+001032
+001033
+001034
+001035
+001036
+001037
+001038
+001039
+001040
+001041
+001042
+001043
+001044
+001045
+001046
+001047
+001048
+001049
+001050
+001051
+001052
+001053
+001054
+001055
+001056
+001057
+001058
+001059
+001060
+001061
+001062
+001063
+001064
+001065
+001066
+001067
+001068
+001069
+001070
+001071
+001072
+001073
+001074
+001075
+001076
+001077
+001078
+001079
+001080
+001081
+001082
+001083
+001084
+001085
+001086
+001087
+001088
+001089
+001090
+001091
+001092
+001093
+001094
+001095
+001096
+001097
+001098
+001099
+001100
+001101
+001102
+001103
+001104
+001105
+001106
+001107
+001108
+001109
+001110
+001111
+001112
+001113
+001114
+001115
+001116
+001117
+001118
+001119
+001120
+001121
+001122
+001123
+001124
+001125
+001126
+001127
+001128
+001129
+001130
+001131
+001132
+001133
+001134
+001135
+001136
+001137
+001138
+001139
+001140
+001141
+001142
+001143
+001144
+001145
+001146
+001147
+001148
+001149
+001150
+001151
+001152
+001153
+001154
+001155
+001156
+001157
+001158
+001159
+001160
+001161
+001162
+001163
+001164
+001165
+001166
+001167
+001168
+001169
+001170
+001171
+001172
+001173
+001174
+001175
+001176
+001177
+001178
+001179
+001180
+001181
+001182
+001183
+001184
+001185
+001186
+001187
+001188
+001189
+001190
+001191
+001192
+001193
+001194
+001195
+001196
+001197
+001198
+001199
+001200
+001201
+001202
+001203
+001204
+001205
+001206
+001207
+001208
+001209
+001210
+001211
+001212
+001213
+001214
+001215
+001216
+001217
+001218
+001219
+001220
+001221
+001222
+001223
+001224
+001225
+001226
+001227
+001228
+001229
+001230
+001231
+001232
+001233
+001234
+001235
+001236
+001237
+001238
+001239
+001240
+001241
+001242
+001243
+001244
+001245
+001246
+001247
+001248
+001249
+001250
+001251
+001252
+001253
+001254
+001255
+001256
+001257
+001258
+001259
+001260
+001261
+001262
+001263
+001264
+001265
+001266
+001267
+001268
+001269
+001270
+001271
+001272
+001273
+001274
+001275
+001276
+001277
+001278
+001279
+001280
+001281
+001282
+001283
+001284
+001285
+001286
+001287
+001288
+001289
+001290
+001291
+001292
+001293
+001294
+001295
+001296
+001297
+001298
+001299
+001300
+001301
+001302
+001303
+001304
+001305
+001306
+001307
+001308
+001309
+001310
+001311
+001312
+001313
+001314
+001315
+001316
+001317
+001318
+001319
+001320
+001321
+001322
+001323
+001324
+001325
+001326
+001327
+001328
+001329
+001330
+001331
+001332
+001333
+001334
+001335
+001336
+001337
+001338
+001339
+001340
+001341
+001342
+001343
+001344
+001345
+001346
+001347
+001348
+001349
+001350
+001351
+001352
+001353
+001354
+001355
+001356
+001357
+001358
+001359
+001360
+001361
+001362
+001363
+001364
+001365
+001366
+001367
+001368
+001369
+001370
+001371
+001372
+001373
+001374
+001375
+001376
+001377
+001378
+001379
+001380
+001381
+001382
+001383
+001384
+001385
+001386
+001387
+001388
+001389
+001390
+001391
+001392
+001393
+001394
+001395
+001396
+001397
+001398
+001399
+001400
+001401
+001402
+001403
+001404
+001405
+001406
+001407
+001408
+001409
+001410
+001411
+001412
+001413
+001414
+001415
+001416
+001417
+001418
+001419
+001420
+001421
+001422
+001423
+001424
+001425
+001426
+001427
+001428
+001429
+001430
+001431
+001432
+001433
+001434
+001435
+001436
+001437
+001438
+001439
+001440
+001441
+001442
+001443
+001444
+001445
+001446
+001447
+001448
+001449
+001450
+001451
+001452
+001453
+001454
+001455
+001456
+001457
+001458
+001459
+001460
+001461
+001462
+001463
+001464
+001465
+001466
+001467
+001468
+001469
+001470
+001471
+001472
+001473
+001474
+001475
+001476
+001477
+001478
+001479
+001480
+001481
+001482
+001483
+001484
+001485
+001486
+001487
+001488
+001489
+001490
+001491
+001492
+001493
+001494
+001495
+001496
+001497
+001498
+001499
+001500
+001501
+001502
+001503
+001504
+001505
+001506
+001507
+001508
+001509
+001510
+001511
+001512
+001513
+001514
+001515
+001516
+001517
+001518
+001519
+001520
+001521
+001522
+001523
+001524
+001525
+001526
+001527
+001528
+001529
+001530
+001531
+001532
+001533
+001534
+001535
+001536
+001537
+001538
+001539
+001540
+001541
+001542
+001543
+001544
+001545
+001546
+001547
+001548
+001549
+001550
+001551
+001552
+001553
+001554
+001555
+001556
+001557
+001558
+001559
+001560
+001561
+001562
+001563
+001564
+001565
+001566
+001567
+001568
+001569
+001570
+001571
+001572
+001573
+001574
+001575
+001576
+001577
+001578
+001579
+001580
+001581
+001582
+001583
+001584
+001585
+001586
+001587
+001588
+001589
+001590
+001591
+001592
+001593
+001594
+001595
+001596
+001597
+001598
+001599
+001600
+001601
+001602
+001603
+001604
+001605
+001606
+001607
+001608
+001609
+001610
+001611
+001612
+001613
+001614
+001615
+001616
+001617
+001618
+001619
+001620
+001621
+001622
+001623
+001624
+001625
+001626
+001627
+001628
+001629
+001630
+001631
+001632
+001633
+001634
+001635
+001636
+001637
+001638
+001639
+001640
+001641
+001642
+001643
+001644
+001645
+001646
+001647
+001648
+001649
+001650
+001651
+001652
+001653
+001654
+001655
+001656
+001657
+001658
+001659
+001660
+001661
+001662
+001663
+001664
+001665
+001666
+001667
+001668
+001669
+001670
+001671
+001672
+001673
+001674
+001675
+001676
+001677
+001678
+001679
+001680
+001681
+001682
+001683
+001684
+001685
+001686
+001687
+001688
+001689
+001690
+001691
+001692
+001693
+001694
+001695
+001696
+001697
+001698
+001699
+001700
+001701
+001702
+001703
+001704
+001705
+001706
+001707
+001708
+001709
+001710
+001711
+001712
+001713
+001714
+001715
+001716
+001717
+001718
+001719
+001720
+001721
+001722
+001723
+001724
+001725
+001726
+001727
+001728
+001729
+001730
+001731
+001732
+001733
+001734
+001735
+001736
+001737
+001738
+001739
+001740
+001741
+001742
+001743
+001744
+001745
+001746
+001747
+001748
+001749
+001750
+001751
+001752
+001753
+001754
+001755
+001756
+001757
+001758
+001759
+001760
+001761
+001762
+001763
+001764
+001765
+001766
+001767
+001768
+001769
+001770
+001771
+001772
+001773
+001774
+001775
+001776
+001777
+001778
+001779
+001780
+001781
+001782
+001783
+001784
+001785
+001786
+001787
+001788
+001789
+001790
+001791
+001792
+001793
+001794
+001795
+001796
+001797
+001798
+001799
+001800
+001801
+001802
+001803
+001804
+001805
+001806
+001807
+001808
+001809
+001810
+001811
+001812
+001813
+001814
+001815
+001816
+001817
+001818
+001819
+001820
+001821
+001822
+001823
+001824
+001825
+001826
+001827
+001828
+001829
+001830
+001831
+001832
+001833
+001834
+001835
+001836
+001837
+001838
+001839
+001840
+001841
+001842
+001843
+001844
+001845
+001846
+001847
+001848
+001849
+001850
+001851
+001852
+001853
+001854
+001855
+001856
+001857
+001858
+001859
+001860
+001861
+001862
+001863
+001864
+001865
+001866
+001867
+001868
+001869
+001870
+001871
+001872
+001873
+001874
+001875
+001876
+001877
+001878
+001879
+001880
+001881
+001882
+001883
+001884
+001885
+001886
+001887
+001888
+001889
+001890
+001891
+001892
+001893
+001894
+001895
+001896
+001897
+001898
+001899
+001900
+001901
+001902
+001903
+001904
+001905
+001906
+001907
+001908
+001909
+001910
+001911
+001912
+001913
+001914
+001915
+001916
+001917
+001918
+001919
+001920
+001921
+001922
+001923
+001924
+001925
+001926
+001927
+001928
+001929
+001930
+001931
+001932
+001933
+001934
+001935
+001936
+001937
+001938
+001939
+001940
+001941
+001942
+001943
+001944
+001945
+001946
+001947
+001948
+001949
+001950
+001951
+001952
+001953
+001954
+001955
+001956
+001957
+001958
+001959
+001960
+001961
+001962
+001963
+001964
+001965
+001966
+001967
+001968
+001969
+001970
+001971
+001972
+001973
+001974
+001975
+001976
+001977
+001978
+001979
+001980
+001981
+001982
+001983
+001984
+001985
+001986
+001987
+001988
+001989
+001990
+001991
+001992
+001993
+001994
+001995
+001996
+001997
+001998
+001999
+002000
+002001
+002002
+002003
+002004
+002005
+002006
+002007
+002008
+002009
+002010
+002011
+002012
+002013
+002014
+002015
+002016
+002017
+002018
+002019
+002020
+002021
+002022
+002023
+002024
+002025
+002026
+002027
+002028
+002029
+002030
+002031
+002032
+002033
+002034
+002035
+002036
+002037
+002038
+002039
+002040
+002041
+002042
+002043
+002044
+002045
+002046
+002047
+002048
+002049
+002050
+002051
+002052
+002053
+002054
+002055
+002056
+002057
+002058
+002059
+002060
+002061
+002062
+002063
+002064
+002065
+002066
+002067
+002068
+002069
+002070
+002071
+002072
+002073
+002074
+002075
+002076
+002077
+002078
+002079
+002080
+002081
+002082
+002083
+002084
+002085
+002086
+002087
+002088
+002089
+002090
+002091
+002092
+002093
+002094
+002095
+002096
+002097
+002098
+002099
+002100
+002101
+002102
+002103
+002104
+002105
+002106
+002107
+002108
+002109
+002110
+002111
+002112
+002113
+002114
+002115
+002116
+002117
+002118
+002119
+002120
+002121
+002122
+002123
+002124
+002125
+002126
+002127
+002128
+002129
+002130
+002131
+002132
+002133
+002134
+002135
+002136
+002137
+002138
+002139
+002140
+002141
+002142
+002143
+002144
+002145
+002146
+002147
+002148
+002149
+002150
+002151
+002152
+002153
+002154
+002155
+002156
+002157
+002158
+002159
+002160
+002161
+002162
+002163
+002164
+002165
+002166
+002167
+002168
+002169
+002170
+002171
+002172
+002173
+002174
+002175
+002176
+002177
+002178
+002179
+002180
+002181
+002182
+002183
+002184
+002185
+002186
+002187
+002188
+002189
+002190
+002191
+002192
+002193
+002194
+002195
+002196
+002197
+002198
+002199
+002200
+002201
+002202
+002203
+002204
+002205
+002206
+002207
+002208
+002209
+002210
+002211
+002212
+002213
+002214
+002215
+002216
+002217
+002218
+002219
+002220
+002221
+002222
+002223
+002224
+002225
+002226
+002227
+002228
+002229
+002230
+002231
+002232
+002233
+002234
+002235
+002236
+002237
+002238
+002239
+002240
+002241
+002242
+002243
+002244
+002245
+002246
+002247
+002248
+002249
+002250
+002251
+002252
+002253
+002254
+002255
+002256
+002257
+002258
+002259
+002260
+002261
+002262
+002263
+002264
+002265
+002266
+002267
+002268
+002269
+002270
+002271
+002272
+002273
+002274
+002275
+002276
+002277
+002278
+002279
+002280
+002281
+002282
+002283
+002284
+002285
+002286
+002287
+002288
+002289
+002290
+002291
+002292
+002293
+002294
+002295
+002296
+002297
+002298
+002299
+002300
+002301
+002302
+002303
+002304
+002305
+002306
+002307
+002308
+002309
+002310
+002311
+002312
+002313
+002314
+002315
+002316
+002317
+002318
+002319
+002320
+002321
+002322
+002323
+002324
+002325
+002326
+002327
+002328
+002329
+002330
+002331
+002332
+002333
+002334
+002335
+002336
+002337
+002338
+002339
+002340
+002341
+002342
+002343
+002344
+002345
+002346
+002347
+002348
+002349
+002350
+002351
+002352
+002353
+002354
+002355
+002356
+002357
+002358
+002359
+002360
+002361
+002362
+002363
+002364
+002365
+002366
+002367
+002368
+002369
+002370
+002371
+002372
+002373
+002374
+002375
+002376
+002377
+002378
+002379
+002380
+002381
+002382
+002383
+002384
+002385
+002386
+002387
+002388
+002389
+002390
+002391
+002392
+002393
+002394
+002395
+002396
+002397
+002398
+002399
+002400
+002401
+002402
+002403
+002404
+002405
+002406
+002407
+002408
+002409
+002410
+002411
+002412
+002413
+002414
+002415
+002416
+002417
+002418
+002419
+002420
+002421
+002422
+002423
+002424
+002425
+002426
+002427
+002428
+002429
+002430
+002431
+002432
+002433
+002434
+002435
+002436
+002437
+002438
+002439
+002440
+002441
+002442
+002443
+002444
+002445
+002446
+002447
+002448
+002449
+002450
+002451
+002452
+002453
+002454
+002455
+002456
+002457
+002458
+002459
+002460
+002461
+002462
+002463
+002464
+002465
+002466
+002467
+002468
+002469
+002470
+002471
+002472
+002473
+002474
+002475
+002476
+002477
+002478
+002479
+002480
+002481
+002482
+002483
+002484
+002485
+002486
+002487
+002488
+002489
+002490
+002491
+002492
+002493
+002494
+002495
+002496
+002497
+002498
+002499
+002500
+002501
+002502
+002503
+002504
+002505
+002506
+002507
+002508
+002509
+002510
+002511
+002512
+002513
+002514
+002515
+002516
+002517
+002518
+002519
+002520
+002521
+002522
+002523
+002524
+002525
+002526
+002527
+002528
+002529
+002530
+002531
+002532
+002533
+002534
+002535
+002536
+002537
+002538
+002539
+002540
+002541
+002542
+002543
+002544
+002545
+002546
+002547
+002548
+002549
+002550
+002551
+002552
+002553
+002554
+002555
+002556
+002557
+002558
+002559
+002560
+002561
+002562
+002563
+002564
+002565
+002566
+002567
+002568
+002569
+002570
+002571
+002572
+002573
+002574
+002575
+002576
+002577
+002578
+002579
+002580
+002581
+002582
+002583
+002584
+002585
+002586
+002587
+002588
+002589
+002590
+002591
+002592
+002593
+002594
+002595
+002596
+002597
+002598
+002599
+002600
+002601
+002602
+002603
+002604
+002605
+002606
+002607
+002608
+002609
+002610
+002611
+002612
+002613
+002614
+002615
+002616
+002617
+002618
+002619
+002620
+002621
+002622
+002623
+002624
+002625
+002626
+002627
+002628
+002629
+002630
+002631
+002632
+002633
+002634
+002635
+002636
+002637
+002638
+002639
+002640
+002641
+002642
+002643
+002644
+002645
+002646
+002647
+002648
+002649
+002650
+002651
+002652
+002653
+002654
+002655
+002656
+002657
+002658
+002659
+002660
+002661
+002662
+002663
+002664
+002665
+002666
+002667
+002668
+002669
+002670
+002671
+002672
+002673
+002674
+002675
+002676
+002677
+002678
+002679
+002680
+002681
+002682
+002683
+002684
+002685
+002686
+002687
+002688
+002689
+002690
+002691
+002692
+002693
+002694
+002695
+002696
+002697
+002698
+002699
+002700
+002701
+002702
+002703
+002704
+002705
+002706
+002707
+002708
+002709
+002710
+002711
+002712
+002713
+002714
+002715
+002716
+002717
+002718
+002719
+002720
+002721
+002722
+002723
+002724
+002725
+002726
+002727
+002728
+002729
+002730
+002731
+002732
+002733
+002734
+002735
+002736
+002737
+002738
+002739
+002740
+002741
+002742
+002743
+002744
+002745
+002746
+002747
+002748
+002749
+002750
+002751
+002752
+002753
+002754
+002755
+002756
+002757
+002758
+002759
+002760
+002761
+002762
+002763
+002764
+002765
+002766
+002767
+002768
+002769
+002770
+002771
+002772
+002773
+002774
+002775
+002776
+002777
+002778
+002779
+002780
+002781
+002782
+002783
+002784
+002785
+002786
+002787
+002788
+002789
+002790
+002791
+002792
+002793
+002794
+002795
+002796
+002797
+002798
+002799
+002800
+002801
+002802
+002803
+002804
+002805
+002806
+002807
+002808
+002809
+002810
+002811
+002812
+002813
+002814
+002815
+002816
+002817
+002818
+002819
+002820
+002821
+002822
+002823
+002824
+002825
+002826
+002827
+002828
+002829
+002830
+002831
+002832
+002833
+002834
+002835
+002836
+002837
+002838
+002839
+002840
+002841
+002842
+002843
+002844
+002845
+002846
+002847
+002848
+002849
+002850
+002851
+002852
+002853
+002854
+002855
+002856
+002857
+002858
+002859
+002860
+002861
+002862
+002863
+002864
+002865
+002866
+002867
+002868
+002869
+002870
+002871
+002872
+002873
+002874
+002875
+002876
+002877
+002878
+002879
+002880
+002881
+002882
+002883
+002884
+002885
+002886
+002887
+002888
+002889
+002890
+002891
+002892
+002893
+002894
+002895
+002896
+002897
+002898
+002899
+002900
+002901
+002902
+002903
+002904
+002905
+002906
+002907
+002908
+002909
+002910
+002911
+002912
+002913
+002914
+002915
+002916
+002917
+002918
+002919
+002920
+002921
+002922
+002923
+002924
+002925
+002926
+002927
+002928
+002929
+002930
+002931
+002932
+002933
+002934
+002935
+002936
+002937
+002938
+002939
+002940
+002941
+002942
+002943
+002944
+002945
+002946
+002947
+002948
+002949
+002950
+002951
+002952
+002953
+002954
+002955
+002956
+002957
+002958
+002959
+002960
+002961
+002962
+002963
+002964
+002965
+002966
+002967
+002968
+002969
+002970
+002971
+002972
+002973
+002974
+002975
+002976
+002977
+002978
+002979
+002980
+002981
+002982
+002983
+002984
+002985
+002986
+002987
+002988
+002989
+002990
+002991
+002992
+002993
+002994
+002995
+002996
+002997
+002998
+002999
+003000
+003001
+003002
+003003
+003004
+003005
+003006
+003007
+003008
+003009
+003010
+003011
+003012
+003013
+003014
+003015
+003016
+003017
+003018
+003019
+003020
+003021
+003022
+003023
+003024
+003025
+003026
+003027
+003028
+003029
+003030
+003031
+003032
+003033
+003034
+003035
+003036
+003037
+003038
+003039
+003040
+003041
+003042
+003043
+003044
+003045
+003046
+003047
+003048
+003049
+003050
+003051
+003052
+003053
+003054
+003055
+003056
+003057
+003058
+003059
+003060
+003061
+003062
+003063
+003064
+003065
+003066
+003067
+003068
+003069
+003070
+003071
+003072
+003073
+003074
+003075
+003076
+003077
+003078
+003079
+003080
+003081
+003082
+003083
+003084
+003085
+003086
+003087
+003088
+003089
+003090
+003091
+003092
+003093
+003094
+003095
+003096
+003097
+003098
+003099
+003100
+003101
+003102
+003103
+003104
+003105
+003106
+003107
+003108
+003109
+003110
+003111
+003112
+003113
+003114
+003115
+003116
+003117
+003118
+003119
+003120
+003121
+003122
+003123
+003124
+003125
+003126
+003127
+003128
+003129
+003130
+003131
+003132
+003133
+003134
+003135
+003136
+003137
+003138
+003139
+003140
+003141
+003142
+003143
+003144
+003145
+003146
+003147
+003148
+003149
+003150
+003151
+003152
+003153
+003154
+003155
+003156
+003157
+003158
+003159
+003160
+003161
+003162
+003163
+003164
+003165
+003166
+003167
+003168
+003169
+003170
+003171
+003172
+003173
+003174
+003175
+003176
+003177
+003178
+003179
+003180
+003181
+003182
+003183
+003184
+003185
+003186
+003187
+003188
+003189
+003190
+003191
+003192
+003193
+003194
+003195
+003196
+003197
+003198
+003199
+003200
+003201
+003202
+003203
+003204
+003205
+003206
+003207
+003208
+003209
+003210
+003211
+003212
+003213
+003214
+003215
+003216
+003217
+003218
+003219
+003220
+003221
+003222
+003223
+003224
+003225
+003226
+003227
+003228
+003229
+003230
+003231
+003232
+003233
+003234
+003235
+003236
+003237
+003238
+003239
+003240
+003241
+003242
+003243
+003244
+003245
+003246
+003247
+003248
+003249
+003250
+003251
+003252
+003253
+003254
+003255
+003256
+003257
+003258
+003259
+003260
+003261
+003262
+003263
+003264
+003265
+003266
+003267
+003268
+003269
+003270
+003271
+003272
+003273
+003274
+003275
+003276
+003277
+003278
+003279
+003280
+003281
+003282
+003283
+003284
+003285
+003286
+003287
+003288
+003289
+003290
+003291
+003292
+003293
+003294
+003295
+003296
+003297
+003298
+003299
+003300
+003301
+003302
+003303
+003304
+003305
+003306
+003307
+003308
+003309
+003310
+003311
+003312
+003313
+003314
+003315
+003316
+003317
+003318
+003319
+003320
+003321
+003322
+003323
+003324
+003325
+003326
+003327
+003328
+003329
+003330
+003331
+003332
+003333
+003334
+003335
+003336
+003337
+003338
+003339
+003340
+003341
+003342
+003343
+003344
+003345
+003346
+003347
+003348
+003349
+003350
+003351
+003352
+003353
+003354
+003355
+003356
+003357
+003358
+003359
+003360
+003361
+003362
+003363
+003364
+003365
+003366
+003367
+003368
+003369
+003370
+003371
+003372
+003373
+003374
+003375
+003376
+003377
+003378
+003379
+003380
+003381
+003382
+003383
+003384
+003385
+003386
+003387
+003388
+003389
+003390
+003391
+003392
+003393
+003394
+003395
+003396
+003397
+003398
+003399
+003400
+003401
+003402
+003403
+003404
+003405
+003406
+003407
+003408
+003409
+003410
+003411
+003412
+003413
+003414
+003415
+003416
+003417
+003418
+003419
+003420
+003421
+003422
+003423
+003424
+003425
+003426
+003427
+003428
+003429
+003430
+003431
+003432
+003433
+003434
+003435
+003436
+003437
+003438
+003439
+003440
+003441
+003442
+003443
+003444
+003445
+003446
+003447
+003448
+003449
+003450
+003451
+003452
+003453
+003454
+003455
+003456
+003457
+003458
+003459
+003460
+003461
+003462
+003463
+003464
+003465
+003466
+003467
+003468
+003469
+003470
+003471
+003472
+003473
+003474
+003475
+003476
+003477
+003478
+003479
+003480
+003481
+003482
+003483
+003484
+003485
+003486
+003487
+003488
+003489
+003490
+003491
+003492
+003493
+003494
+003495
+003496
+003497
+003498
+003499
+003500
+003501
+003502
+003503
+003504
+003505
+003506
+003507
+003508
+003509
+003510
+003511
+003512
+003513
+003514
+003515
+003516
+003517
+003518
+003519
+003520
+003521
+003522
+003523
+003524
+003525
+003526
+003527
+003528
+003529
+003530
+003531
+003532
+003533
+003534
+003535
+003536
+003537
+003538
+003539
+003540
+003541
+003542
+003543
+003544
+003545
+003546
+003547
+003548
+003549
+003550
+003551
+003552
+003553
+003554
+003555
+003556
+003557
+003558
+003559
+003560
+003561
+003562
+003563
+003564
+003565
+003566
+003567
+003568
+003569
+003570
+003571
+003572
+003573
+003574
+003575
+003576
+003577
+003578
+003579
+003580
+003581
+003582
+003583
+003584
+003585
+003586
+003587
+003588
+003589
+003590
+003591
+003592
+003593
+003594
+003595
+003596
+003597
+003598
+003599
+003600
+003601
+003602
+003603
+003604
+003605
+003606
+003607
+003608
+003609
+003610
+003611
+003612
+003613
+003614
+003615
+003616
+003617
+003618
+003619
+003620
+003621
+003622
+003623
+003624
+003625
+003626
+003627
+003628
+003629
+003630
+003631
+003632
+003633
+003634
+003635
+003636
+003637
+003638
+003639
+003640
+003641
+003642
+003643
+003644
+003645
+003646
+003647
+003648
+003649
+003650
+003651
+003652
+003653
+003654
+003655
+003656
+003657
+003658
+003659
+003660
+003661
+003662
+003663
+003664
+003665
+003666
+003667
+003668
+003669
+003670
+003671
+003672
+003673
+003674
+003675
+003676
+003677
+003678
+003679
+003680
+003681
+003682
+003683
+003684
+003685
+003686
+003687
+003688
+003689
+003690
+003691
+003692
+003693
+003694
+003695
+003696
+003697
+003698
+003699
+003700
+003701
+003702
+003703
+003704
+003705
+003706
+003707
+003708
+003709
+003710
+003711
+003712
+003713
+003714
+003715
+003716
+003717
+003718
+003719
+003720
+003721
+003722
+003723
+003724
+003725
+003726
+003727
+003728
+003729
+003730
+003731
+003732
+003733
+003734
+003735
+003736
+003737
+003738
+003739
+003740
+003741
+003742
+003743
+003744
+003745
+003746
+003747
+003748
+003749
+003750
+003751
+003752
+003753
+003754
+003755
+003756
+003757
+003758
+003759
+003760
+003761
+003762
+003763
+003764
+003765
+003766
+003767
+003768
+003769
+003770
+003771
+003772
+003773
+003774
+003775
+003776
+003777
+003778
+003779
+003780
+003781
+003782
+003783
+003784
+003785
+003786
+003787
+003788
+003789
+003790
+003791
+003792
+003793
+003794
+003795
+003796
+003797
+003798
+003799
+003800
+003801
+003802
+003803
+003804
+003805
+003806
+003807
+003808
+003809
+003810
+003811
+003812
+003813
+003814
+003815
+003816
+003817
+003818
+003819
+003820
+003821
+003822
+003823
+003824
+003825
+003826
+003827
+003828
+003829
+003830
+003831
+003832
+003833
+003834
+003835
+003836
+003837
+003838
+003839
+003840
+003841
+003842
+003843
+003844
+003845
+003846
+003847
+003848
+003849
+003850
+003851
+003852
+003853
+003854
+003855
+003856
+003857
+003858
+003859
+003860
+003861
+003862
+003863
+003864
+003865
+003866
+003867
+003868
+003869
+003870
+003871
+003872
+003873
+003874
+003875
+003876
+003877
+003878
+003879
+003880
+003881
+003882
+003883
+003884
+003885
+003886
+003887
+003888
+003889
+003890
+003891
+003892
+003893
+003894
+003895
+003896
+003897
+003898
+003899
+003900
+003901
+003902
+003903
+003904
+003905
+003906
+003907
+003908
+003909
+003910
+003911
+003912
+003913
+003914
+003915
+003916
+003917
+003918
+003919
+003920
+003921
+003922
+003923
+003924
+003925
+003926
+003927
+003928
+003929
+003930
+003931
+003932
+003933
+003934
+003935
+003936
+003937
+003938
+003939
+003940
+003941
+003942
+003943
+003944
+003945
+003946
+003947
+003948
+003949
+003950
+003951
+003952
+003953
+003954
+003955
+003956
+003957
+003958
+003959
+003960
+003961
+003962
+003963
+003964
+003965
+003966
+003967
+003968
+003969
+003970
+003971
+003972
+003973
+003974
+003975
+003976
+003977
+003978
+003979
+003980
+003981
+003982
+003983
+003984
+003985
+003986
+003987
+003988
+003989
+003990
+003991
+003992
+003993
+003994
+003995
+003996
+003997
+003998
+003999
+004000
+004001
+004002
+004003
+004004
+004005
+004006
+004007
+004008
+004009
+004010
+004011
+004012
+004013
+004014
+004015
+004016
+004017
+004018
+004019
+004020
+004021
+004022
+004023
+004024
+004025
+004026
+004027
+004028
+004029
+004030
+004031
+004032
+004033
+004034
+004035
+004036
+004037
+004038
+004039
+004040
+004041
+004042
+004043
+004044
+004045
+004046
+004047
+004048
+004049
+004050
+004051
+004052
+004053
+004054
+004055
+004056
+004057
+004058
+004059
+004060
+004061
+004062
+004063
+004064
+004065
+004066
+004067
+004068
+004069
+004070
+004071
+004072
+004073
+004074
+004075
+004076
+004077
+004078
+004079
+004080
+004081
+004082
+004083
+004084
+004085
+004086
+004087
+004088
+004089
+004090
+004091
+004092
+004093
+004094
+004095
+004096
+004097
+004098
+004099
+004100
+004101
+004102
+004103
+004104
+004105
+004106
+004107
+004108
+004109
+004110
+004111
+004112
+004113
+004114
+004115
+004116
+004117
+004118
+004119
+004120
+004121
+004122
+004123
+004124
+004125
+004126
+004127
+004128
+004129
+004130
+004131
+004132
+004133
+004134
+004135
+004136
+004137
+004138
+004139
+004140
+004141
+004142
+004143
+004144
+004145
+004146
+004147
+004148
+004149
+004150
+004151
+004152
+004153
+004154
+004155
+004156
+004157
+004158
+004159
+004160
+004161
+004162
+004163
+004164
+004165
+004166
+004167
+004168
+004169
+004170
+004171
+004172
+004173
+004174
+004175
+004176
+004177
+004178
+004179
+004180
+004181
+004182
+004183
+004184
+004185
+004186
+004187
+004188
+004189
+004190
+004191
+004192
+004193
+004194
+004195
+004196
+004197
+004198
+004199
+004200
+004201
+004202
+004203
+004204
+004205
+004206
+004207
+004208
+004209
+004210
+004211
+004212
+004213
+004214
+004215
+004216
+004217
+004218
+004219
+004220
+004221
+004222
+004223
+004224
+004225
+004226
+004227
+004228
+004229
+004230
+004231
+004232
+004233
+004234
+004235
+004236
+004237
+004238
+004239
+004240
+004241
+004242
+004243
+004244
+004245
+004246
+004247
+004248
+004249
+004250
+004251
+004252
+004253
+004254
+004255
+004256
+004257
+004258
+004259
+004260
+004261
+004262
+004263
+004264
+004265
+004266
+004267
+004268
+004269
+004270
+004271
+004272
+004273
+004274
+004275
+004276
+004277
+004278
+004279
+004280
+004281
+004282
+004283
+004284
+004285
+004286
+004287
+004288
+004289
+004290
+004291
+004292
+004293
+004294
+004295
+004296
+004297
+004298
+004299
+004300
+004301
+004302
+004303
+004304
+004305
+004306
+004307
+004308
+004309
+004310
+004311
+004312
+004313
+004314
+004315
+004316
+004317
+004318
+004319
+004320
+004321
+004322
+004323
+004324
+004325
+004326
+004327
+004328
+004329
+004330
+004331
+004332
+004333
+004334
+004335
+004336
+004337
+004338
+004339
+004340
+004341
+004342
+004343
+004344
+004345
+004346
+004347
+004348
+004349
+004350
+004351
+004352
+004353
+004354
+004355
+004356
+004357
+004358
+004359
+004360
+004361
+004362
+004363
+004364
+004365
+004366
+004367
+004368
+004369
+004370
+004371
+004372
+004373
+004374
+004375
+004376
+004377
+004378
+004379
+004380
+004381
+004382
+004383
+004384
+004385
+004386
+004387
+004388
+004389
+004390
+004391
+004392
+004393
+004394
+004395
+004396
+004397
+004398
+004399
+004400
+004401
+004402
+004403
+004404
+004405
+004406
+004407
+004408
+004409
+004410
+004411
+004412
+004413
+004414
+004415
+004416
+004417
+004418
+004419
+004420
+004421
+004422
+004423
+004424
+004425
+004426
+004427
+004428
+004429
+004430
+004431
+004432
+004433
+004434
+004435
+004436
+004437
+004438
+004439
+004440
+004441
+004442
+004443
+004444
+004445
+004446
+004447
+004448
+004449
+004450
+004451
+004452
+004453
+004454
+004455
+004456
+004457
+004458
+004459
+004460
+004461
+004462
+004463
+004464
+004465
+004466
+004467
+004468
+004469
+004470
+004471
+004472
+004473
+004474
+004475
+004476
+004477
+004478
+004479
+004480
+004481
+004482
+004483
+004484
+004485
+004486
+004487
+004488
+004489
+004490
+004491
+004492
+004493
+004494
+004495
+004496
+004497
+004498
+004499
+004500
+004501
+004502
+004503
+004504
+004505
+004506
+004507
+004508
+004509
+004510
+004511
+004512
+004513
+004514
+004515
+004516
+004517
+004518
+004519
+004520
+004521
+004522
+004523
+004524
+004525
+004526
+004527
+004528
+004529
+004530
+004531
+004532
+004533
+004534
+004535
+004536
+004537
+004538
+004539
+004540
+004541
+004542
+004543
+004544
+004545
+004546
+004547
+004548
+004549
+004550
+004551
+004552
+004553
+004554
+004555
+004556
+004557
+004558
+004559
+004560
+004561
+004562
+004563
+004564
+004565
+004566
+004567
+004568
+004569
+004570
+004571
+004572
+004573
+004574
+004575
+004576
+004577
+004578
+004579
+004580
+004581
+004582
+004583
+004584
+004585
+004586
+004587
+004588
+004589
+004590
+004591
+004592
+004593
+004594
+004595
+004596
+004597
+004598
+004599
+004600
+004601
+004602
+004603
+004604
+004605
+004606
+004607
+004608
+004609
+004610
+004611
+004612
+004613
+004614
+004615
+004616
+004617
+004618
+004619
+004620
+004621
+004622
+004623
+004624
+004625
+004626
+004627
+004628
+004629
+004630
+004631
+004632
+004633
+004634
+004635
+004636
+004637
+004638
+004639
+004640
+004641
+004642
+004643
+004644
+004645
+004646
+004647
+004648
+004649
+004650
+004651
+004652
+004653
+004654
+004655
+004656
+004657
+004658
+004659
+004660
+004661
+004662
+004663
+004664
+004665
+004666
+004667
+004668
+004669
+004670
+004671
+004672
+004673
+004674
+004675
+004676
+004677
+004678
+004679
+004680
+004681
+004682
+004683
+004684
+004685
+004686
+004687
+004688
+004689
+004690
+004691
+004692
+004693
+004694
+004695
+004696
+004697
+004698
+004699
+004700
+004701
+004702
+004703
+004704
+004705
+004706
+004707
+004708
+004709
+004710
+004711
+004712
+004713
+004714
+004715
+004716
+004717
+004718
+004719
+004720
+004721
+004722
+004723
+004724
+004725
+004726
+004727
+004728
+004729
+004730
+004731
+004732
+004733
+004734
+004735
+004736
+004737
+004738
+004739
+004740
+004741
+004742
+004743
+004744
+004745
+004746
+004747
+004748
+004749
+004750
+004751
+004752
+004753
+004754
+004755
+004756
+004757
+004758
+004759
+004760
+004761
+004762
+004763
+004764
+004765
+004766
+004767
+004768
+004769
+004770
+004771
+004772
+004773
+004774
+004775
+004776
+004777
+004778
+004779
+004780
+004781
+004782
+004783
+004784
+004785
+004786
+004787
+004788
+004789
+004790
+004791
+004792
+004793
+004794
+004795
+004796
+004797
+004798
+004799
+004800
+004801
+004802
+004803
+004804
+004805
+004806
+004807
+004808
+004809
+004810
+004811
+004812
+004813
+004814
+004815
+004816
+004817
+004818
+004819
+004820
+004821
+004822
+004823
+004824
+004825
+004826
+004827
+004828
+004829
+004830
+004831
+004832
+004833
+004834
+004835
+004836
+004837
+004838
+004839
+004840
+004841
+004842
+004843
+004844
+004845
+004846
+004847
+004848
+004849
+004850
+004851
+004852
+004853
+004854
+004855
+004856
+004857
+004858
+004859
+004860
+004861
+004862
+004863
+004864
+004865
+004866
+004867
+004868
+004869
+004870
+004871
+004872
+004873
+004874
+004875
+004876
+004877
+004878
+004879
+004880
+004881
+004882
+004883
+004884
+004885
+004886
+004887
+004888
+004889
+004890
+004891
+004892
+004893
+004894
+004895
+004896
+004897
+004898
+004899
+004900
+004901
+004902
+004903
+004904
+004905
+004906
+004907
+004908
+004909
+004910
+004911
+004912
+004913
+004914
+004915
+004916
+004917
+004918
+004919
+004920
+004921
+004922
+004923
+004924
+004925
+004926
+004927
+004928
+004929
+004930
+004931
+004932
+004933
+004934
+004935
+004936
+004937
+004938
+004939
+004940
+004941
+004942
+004943
+004944
+004945
+004946
+004947
+004948
+004949
+004950
+004951
+004952
+004953
+004954
+004955
+004956
+004957
+004958
+004959
+004960
+004961
+004962
+004963
+004964
+004965
+004966
+004967
+004968
+004969
+004970
+004971
+004972
+004973
+004974
+004975
+004976
+004977
+004978
+004979
+004980
+004981
+004982
+004983
+004984
+004985
+004986
+004987
+004988
+004989
+004990
+004991
+004992
+004993
+004994
+004995
+004996
+004997
+004998
+004999
+005000
+005001
+005002
+005003
+005004
+005005
+005006
+005007
+005008
+005009
+005010
+005011
+005012
+005013
+005014
+005015
+005016
+005017
+005018
+005019
+005020
+005021
+005022
+005023
+005024
+005025
+005026
+005027
+005028
+005029
+005030
+005031
+005032
+005033
+005034
+005035
+005036
+005037
+005038
+005039
+005040
+005041
+005042
+005043
+005044
+005045
+005046
+005047
+005048
+005049
+005050
+005051
+005052
+005053
+005054
+005055
+005056
+005057
+005058
+005059
+005060
+005061
+005062
+005063
+005064
+005065
+005066
+005067
+005068
+005069
+005070
+005071
+005072
+005073
+005074
+005075
+005076
+005077
+005078
+005079
+005080
+005081
+005082
+005083
+005084
+005085
+005086
+005087
+005088
+005089
+005090
+005091
+005092
+005093
+005094
+005095
+005096
+005097
+005098
+005099
+005100
+005101
+005102
+005103
+005104
+005105
+005106
+005107
+005108
+005109
+005110
+005111
+005112
+005113
+005114
+005115
+005116
+005117
+005118
+005119
+005120
+005121
+005122
+005123
+005124
+005125
+005126
+005127
+005128
+005129
+005130
+005131
+005132
+005133
+005134
+005135
+005136
+005137
+005138
+005139
+005140
+005141
+005142
+005143
+005144
+005145
+005146
+005147
+005148
+005149
+005150
+005151
+005152
+005153
+005154
+005155
+005156
+005157
+005158
+005159
+005160
+005161
+005162
+005163
+005164
+005165
+005166
+005167
+005168
+005169
+005170
+005171
+005172
+005173
+005174
+005175
+005176
+005177
+005178
+005179
+005180
+005181
+005182
+005183
+005184
+005185
+005186
+005187
+005188
+005189
+005190
+005191
+005192
+005193
+005194
+005195
+005196
+005197
+005198
+005199
+005200
+005201
+005202
+005203
+005204
+005205
+005206
+005207
+005208
+005209
+005210
+005211
+005212
+005213
+005214
+005215
+005216
+005217
+005218
+005219
+005220
+005221
+005222
+005223
+005224
+005225
+005226
+005227
+005228
+005229
+005230
+005231
+005232
+005233
+005234
+005235
+005236
+005237
+005238
+005239
+005240
+005241
+005242
+005243
+005244
+005245
+005246
+005247
+005248
+005249
+005250
+005251
+005252
+005253
+005254
+005255
+005256
+005257
+005258
+005259
+005260
+005261
+005262
+005263
+005264
+005265
+005266
+005267
+005268
+005269
+005270
+005271
+005272
+005273
+005274
+005275
+005276
+005277
+005278
+005279
+005280
+005281
+005282
+005283
+005284
+005285
+005286
+005287
+005288
+005289
+005290
+005291
+005292
+005293
+005294
+005295
+005296
+005297
+005298
+005299
+005300
+005301
+005302
+005303
+005304
+005305
+005306
+005307
+005308
+005309
+005310
+005311
+005312
+005313
+005314
+005315
+005316
+005317
+005318
+005319
+005320
+005321
+005322
+005323
+005324
+005325
+005326
+005327
+005328
+005329
+005330
+005331
+005332
+005333
+005334
+005335
+005336
+005337
+005338
+005339
+005340
+005341
+005342
+005343
+005344
+005345
+005346
+005347
+005348
+005349
+005350
+005351
+005352
+005353
+005354
+005355
+005356
+005357
+005358
+005359
+005360
+005361
+005362
+005363
+005364
+005365
+005366
+005367
+005368
+005369
+005370
+005371
+005372
+005373
+005374
+005375
+005376
+005377
+005378
+005379
+005380
+005381
+005382
+005383
+005384
+005385
+005386
+005387
+005388
+005389
+005390
+005391
+005392
+005393
+005394
+005395
+005396
+005397
+005398
+005399
+005400
+005401
+005402
+005403
+005404
+005405
+005406
+005407
+005408
+005409
+005410
+005411
+005412
+005413
+005414
+005415
+005416
+005417
+005418
+005419
+005420
+005421
+005422
+005423
+005424
+005425
+005426
+005427
+005428
+005429
+005430
+005431
+005432
+005433
+005434
+005435
+005436
+005437
+005438
+005439
+005440
+005441
+005442
+005443
+005444
+005445
+005446
+005447
+005448
+005449
+005450
+005451
+005452
+005453
+005454
+005455
+005456
+005457
+005458
+005459
+005460
+005461
+005462
+005463
+005464
+005465
+005466
+005467
+005468
+005469
+005470
+005471
+005472
+005473
+005474
+005475
+005476
+005477
+005478
+005479
+005480
+005481
+005482
+005483
+005484
+005485
+005486
+005487
+005488
+005489
+005490
+005491
+005492
+005493
+005494
+005495
+005496
+005497
+005498
+005499
+005500
+005501
+005502
+005503
+005504
+005505
+005506
+005507
+005508
+005509
+005510
+005511
+005512
+005513
+005514
+005515
+005516
+005517
+005518
+005519
+005520
+005521
+005522
+005523
+005524
+005525
+005526
+005527
+005528
+005529
+005530
+005531
+005532
+005533
+005534
+005535
+005536
+005537
+005538
+005539
+005540
+005541
+005542
+005543
+005544
+005545
+005546
+005547
+005548
+005549
+005550
+005551
+005552
+005553
+005554
+005555
+005556
+005557
+005558
+005559
+005560
+005561
+005562
+005563
+005564
+005565
+005566
+005567
+005568
+005569
+005570
+005571
+005572
+005573
+005574
+005575
+005576
+005577
+005578
+005579
+005580
+005581
+005582
+005583
+005584
+005585
+005586
+005587
+005588
+005589
+005590
+005591
+005592
+005593
+005594
+005595
+005596
+005597
+005598
+005599
+005600
+005601
+005602
+005603
+005604
+005605
+005606
+005607
+005608
+005609
+005610
+005611
+005612
+005613
+005614
+005615
+005616
+005617
+005618
+005619
+005620
+005621
+005622
+005623
+005624
+005625
+005626
+005627
+005628
+005629
+005630
+005631
+005632
+005633
+005634
+005635
+005636
+005637
+005638
+005639
+005640
+005641
+005642
+005643
+005644
+005645
+005646
+005647
+005648
+005649
+005650
+005651
+005652
+005653
+005654
+005655
+005656
+005657
+005658
+005659
+005660
+005661
+005662
+005663
+005664
+005665
+005666
+005667
+005668
+005669
+005670
+005671
+005672
+005673
+005674
+005675
+005676
+005677
+005678
+005679
+005680
+005681
+005682
+005683
+005684
+005685
+005686
+005687
+005688
+005689
+005690
+005691
+005692
+005693
+005694
+005695
+005696
+005697
+005698
+005699
+005700
+005701
+005702
+005703
+005704
+005705
+005706
+005707
+005708
+005709
+005710
+005711
+005712
+005713
+005714
+005715
+005716
+005717
+005718
+005719
+005720
+005721
+005722
+005723
+005724
+005725
+005726
+005727
+005728
+005729
+005730
+005731
+005732
+005733
+005734
+005735
+005736
+005737
+005738
+005739
+005740
+005741
+005742
+005743
+005744
+005745
+005746
+005747
+005748
+005749
+005750
+005751
+005752
+005753
+005754
+005755
+005756
+005757
+005758
+005759
+005760
+005761
+005762
+005763
+005764
+005765
+005766
+005767
+005768
+005769
+005770
+005771
+005772
+005773
+005774
+005775
+005776
+005777
+005778
+005779
+005780
+005781
+005782
+005783
+005784
+005785
+005786
+005787
+005788
+005789
+005790
+005791
+005792
+005793
+005794
+005795
+005796
+005797
+005798
+005799
+005800
+005801
+005802
+005803
+005804
+005805
+005806
+005807
+005808
+005809
+005810
+005811
+005812
+005813
+005814
+005815
+005816
+005817
+005818
+005819
+005820
+005821
+005822
+005823
+005824
+005825
+005826
+005827
+005828
+005829
+005830
+005831
+005832
+005833
+005834
+005835
+005836
+005837
+005838
+005839
+005840
+005841
+005842
+005843
+005844
+005845
+005846
+005847
+005848
+005849
+005850
+005851
+005852
+005853
+005854
+005855
+005856
+005857
+005858
+005859
+005860
+005861
+005862
+005863
+005864
+005865
+005866
+005867
+005868
+005869
+005870
+005871
+005872
+005873
+005874
+005875
+005876
+005877
+005878
+005879
+005880
+005881
+005882
+005883
+005884
+005885
+005886
+005887
+005888
+005889
+005890
+005891
+005892
+005893
+005894
+005895
+005896
+005897
+005898
+005899
+005900
+005901
+005902
+005903
+005904
+005905
+005906
+005907
+005908
+005909
+005910
+005911
+005912
+005913
+005914
+005915
+005916
+005917
+005918
+005919
+005920
+005921
+005922
+005923
+005924
+005925
+005926
+005927
+005928
+005929
+005930
+005931
+005932
+005933
+005934
+005935
+005936
+005937
+005938
+005939
+005940
+005941
+005942
+005943
+005944
+005945
+005946
+005947
+005948
+005949
+005950
+005951
+005952
+005953
+005954
+005955
+005956
+005957
+005958
+005959
+005960
+005961
+005962
+005963
+005964
+005965
+005966
+005967
+005968
+005969
+005970
+005971
+005972
+005973
+005974
+005975
+005976
+005977
+005978
+005979
+005980
+005981
+005982
+005983
+005984
+005985
+005986
+005987
+005988
+005989
+005990
+005991
+005992
+005993
+005994
+005995
+005996
+005997
+005998
+005999
+006000
+006001
+006002
+006003
+006004
+006005
+006006
+006007
+006008
+006009
+006010
+006011
+006012
+006013
+006014
+006015
+006016
+006017
+006018
+006019
+006020
+006021
+006022
+006023
+006024
+006025
+006026
+006027
+006028
+006029
+006030
+006031
+006032
+006033
+006034
+006035
+006036
+006037
+006038
+006039
+006040
+006041
+006042
+006043
+006044
+006045
+006046
+006047
+006048
+006049
+006050
+006051
+006052
+006053
+006054
+006055
+006056
+006057
+006058
+006059
+006060
+006061
+006062
+006063
+006064
+006065
+006066
+006067
+006068
+006069
+006070
+006071
+006072
+006073
+006074
+006075
+006076
+006077
+006078
+006079
+006080
+006081
+006082
+006083
+006084
+006085
+006086
+006087
+006088
+006089
+006090
+006091
+006092
+006093
+006094
+006095
+006096
+006097
+006098
+006099
+006100
+006101
+006102
+006103
+006104
+006105
+006106
+006107
+006108
+006109
+006110
+006111
+006112
+006113
+006114
+006115
+006116
+006117
+006118
+006119
+006120
+006121
+006122
+006123
+006124
+006125
+006126
+006127
+006128
+006129
+006130
+006131
+006132
+006133
+006134
+006135
+006136
+006137
+006138
+006139
+006140
+006141
+006142
+006143
+006144
+006145
+006146
+006147
+006148
+006149
+006150
+006151
+006152
+006153
+006154
+006155
+006156
+006157
+006158
+006159
+006160
+006161
+006162
+006163
+006164
+006165
+006166
+006167
+006168
+006169
+006170
+006171
+006172
+006173
+006174
+006175
+006176
+006177
+006178
+006179
+006180
+006181
+006182
+006183
+006184
+006185
+006186
+006187
+006188
+006189
+006190
+006191
+006192
+006193
+006194
+006195
+006196
+006197
+006198
+006199
+006200
+006201
+006202
+006203
+006204
+006205
+006206
+006207
+006208
+006209
+006210
+006211
+006212
+006213
+006214
+006215
+006216
+006217
+006218
+006219
+006220
+006221
+006222
+006223
+006224
+006225
+006226
+006227
+006228
+006229
+006230
+006231
+006232
+006233
+006234
+006235
+006236
+006237
+006238
+006239
+006240
+006241
+006242
+006243
+006244
+006245
+006246
+006247
+006248
+006249
+006250
+006251
+006252
+006253
+006254
+006255
+006256
+006257
+006258
+006259
+006260
+006261
+006262
+006263
+006264
+006265
+006266
+006267
+006268
+006269
+006270
+006271
+006272
+006273
+006274
+006275
+006276
+006277
+006278
+006279
+006280
+006281
+006282
+006283
+006284
+006285
+006286
+006287
+006288
+006289
+006290
+006291
+006292
+006293
+006294
+006295
+006296
+006297
+006298
+006299
+006300
+006301
+006302
+006303
+006304
+006305
+006306
+006307
+006308
+006309
+006310
+006311
+006312
+006313
+006314
+006315
+006316
+006317
+006318
+006319
+006320
+006321
+006322
+006323
+006324
+006325
+006326
+006327
+006328
+006329
+006330
+006331
+006332
+006333
+006334
+006335
+006336
+006337
+006338
+006339
+006340
+006341
+006342
+006343
+006344
+006345
+006346
+006347
+006348
+006349
+006350
+006351
+006352
+006353
+006354
+006355
+006356
+006357
+006358
+006359
+006360
+006361
+006362
+006363
+006364
+006365
+006366
+006367
+006368
+006369
+006370
+006371
+006372
+006373
+006374
+006375
+006376
+006377
+006378
+006379
+006380
+006381
+006382
+006383
+006384
+006385
+006386
+006387
+006388
+006389
+006390
+006391
+006392
+006393
+006394
+006395
+006396
+006397
+006398
+006399
+006400
+006401
+006402
+006403
+006404
+006405
+006406
+006407
+006408
+006409
+006410
+006411
+006412
+006413
+006414
+006415
+006416
+006417
+006418
+006419
+006420
+006421
+006422
+006423
+006424
+006425
+006426
+006427
+006428
+006429
+006430
+006431
+006432
+006433
+006434
+006435
+006436
+006437
+006438
+006439
+006440
+006441
+006442
+006443
+006444
+006445
+006446
+006447
+006448
+006449
+006450
+006451
+006452
+006453
+006454
+006455
+006456
+006457
+006458
+006459
+006460
+006461
+006462
+006463
+006464
+006465
+006466
+006467
+006468
+006469
+006470
+006471
+006472
+006473
+006474
+006475
+006476
+006477
+006478
+006479
+006480
+006481
+006482
+006483
+006484
+006485
+006486
+006487
+006488
+006489
+006490
+006491
+006492
+006493
+006494
+006495
+006496
+006497
+006498
+006499
+006500
+006501
+006502
+006503
+006504
+006505
+006506
+006507
+006508
+006509
+006510
+006511
+006512
+006513
+006514
+006515
+006516
+006517
+006518
+006519
+006520
+006521
+006522
+006523
+006524
+006525
+006526
+006527
+006528
+006529
+006530
+006531
+006532
+006533
+006534
+006535
+006536
+006537
+006538
+006539
+006540
+006541
+006542
+006543
+006544
+006545
+006546
+006547
+006548
+006549
+006550
+006551
+006552
+006553
+006554
+006555
+006556
+006557
+006558
+006559
+006560
+006561
+006562
+006563
+006564
+006565
+006566
+006567
+006568
+006569
+006570
+006571
+006572
+006573
+006574
+006575
+006576
+006577
+006578
+006579
+006580
+006581
+006582
+006583
+006584
+006585
+006586
+006587
+006588
+006589
+006590
+006591
+006592
+006593
+006594
+006595
+006596
+006597
+006598
+006599
+006600
+006601
+006602
+006603
+006604
+006605
+006606
+006607
+006608
+006609
+006610
+006611
+006612
+006613
+006614
+006615
+006616
+006617
+006618
+006619
+006620
+006621
+006622
+006623
+006624
+006625
+006626
+006627
+006628
+006629
+006630
+006631
+006632
+006633
+006634
+006635
+006636
+006637
+006638
+006639
+006640
+006641
+006642
+006643
+006644
+006645
+006646
+006647
+006648
+006649
+006650
+006651
+006652
+006653
+006654
+006655
+006656
+006657
+006658
+006659
+006660
+006661
+006662
+006663
+006664
+006665
+006666
+006667
+006668
+006669
+006670
+006671
+006672
+006673
+006674
+006675
+006676
+006677
+006678
+006679
+006680
+006681
+006682
+006683
+006684
+006685
+006686
+006687
+006688
+006689
+006690
+006691
+006692
+006693
+006694
+006695
+006696
+006697
+006698
+006699
+006700
+006701
+006702
+006703
+006704
+006705
+006706
+006707
+006708
+006709
+006710
+006711
+006712
+006713
+006714
+006715
+006716
+006717
+006718
+006719
+006720
+006721
+006722
+006723
+006724
+006725
+006726
+006727
+006728
+006729
+006730
+006731
+006732
+006733
+006734
+006735
+006736
+006737
+006738
+006739
+006740
+006741
+006742
+006743
+006744
+006745
+006746
+006747
+006748
+006749
+006750
+006751
+006752
+006753
+006754
+006755
+006756
+006757
+006758
+006759
+006760
+006761
+006762
+006763
+006764
+006765
+006766
+006767
+006768
+006769
+006770
+006771
+006772
+006773
+006774
+006775
+006776
+006777
+006778
+006779
+006780
+006781
+006782
+006783
+006784
+006785
+006786
+006787
+006788
+006789
+006790
+006791
+006792
+006793
+006794
+006795
+006796
+006797
+006798
+006799
+006800
+006801
+006802
+006803
+006804
+006805
+006806
+006807
+006808
+006809
+006810
+006811
+006812
+006813
+006814
+006815
+006816
+006817
+006818
+006819
+006820
+006821
+006822
+006823
+006824
+006825
+006826
+006827
+006828
+006829
+006830
+006831
+006832
+006833
+006834
+006835
+006836
+006837
+006838
+006839
+006840
+006841
+006842
+006843
+006844
+006845
+006846
+006847
+006848
+006849
+006850
+006851
+006852
+006853
+006854
+006855
+006856
+006857
+006858
+006859
+006860
+006861
+006862
+006863
+006864
+006865
+006866
+006867
+006868
+006869
+006870
+006871
+006872
+006873
+006874
+006875
+006876
+006877
+006878
+006879
+006880
+006881
+006882
+006883
+006884
+006885
+006886
+006887
+006888
+006889
+006890
+006891
+006892
+006893
+006894
+006895
+006896
+006897
+006898
+006899
+006900
+006901
+006902
+006903
+006904
+006905
+006906
+006907
+006908
+006909
+006910
+006911
+006912
+006913
+006914
+006915
+006916
+006917
+006918
+006919
+006920
+006921
+006922
+006923
+006924
+006925
+006926
+006927
+006928
+006929
+006930
+006931
+006932
+006933
+006934
+006935
+006936
+006937
+006938
+006939
+006940
+006941
+006942
+006943
+006944
+006945
+006946
+006947
+006948
+006949
+006950
+006951
+006952
+006953
+006954
+006955
+006956
+006957
+006958
+006959
+006960
+006961
+006962
+006963
+006964
+006965
+006966
+006967
+006968
+006969
+006970
+006971
+006972
+006973
+006974
+006975
+006976
+006977
+006978
+006979
+006980
+006981
+006982
+006983
+006984
+006985
+006986
+006987
+006988
+006989
+006990
+006991
+006992
+006993
+006994
+006995
+006996
+006997
+006998
+006999
+007000
+007001
+007002
+007003
+007004
+007005
+007006
+007007
+007008
+007009
+007010
+007011
+007012
+007013
+007014
+007015
+007016
+007017
+007018
+007019
+007020
+007021
+007022
+007023
+007024
+007025
+007026
+007027
+007028
+007029
+007030
+007031
+007032
+007033
+007034
+007035
+007036
+007037
+007038
+007039
+007040
+007041
+007042
+007043
+007044
+007045
+007046
+007047
+007048
+007049
+007050
+007051
+007052
+007053
+007054
+007055
+007056
+007057
+007058
+007059
+007060
+007061
+007062
+007063
+007064
+007065
+007066
+007067
+007068
+007069
+007070
+007071
+007072
+007073
+007074
+007075
+007076
+007077
+007078
+007079
+007080
+007081
+007082
+007083
+007084
+007085
+007086
+007087
+007088
+007089
+007090
+007091
+007092
+007093
+007094
+007095
+007096
+007097
+007098
+007099
+007100
+007101
+007102
+007103
+007104
+007105
+007106
+007107
+007108
+007109
+007110
+007111
+007112
+007113
+007114
+007115
+007116
+007117
+007118
+007119
+007120
+007121
+007122
+007123
+007124
+007125
+007126
+007127
+007128
+007129
+007130
+007131
+007132
+007133
+007134
+007135
+007136
+007137
+007138
+007139
+007140
+007141
+007142
+007143
+007144
+007145
+007146
+007147
+007148
+007149
+007150
+007151
+007152
+007153
+007154
+007155
+007156
+007157
+007158
+007159
+007160
+007161
+007162
+007163
+007164
+007165
+007166
+007167
+007168
+007169
+007170
+007171
+007172
+007173
+007174
+007175
+007176
+007177
+007178
+007179
+007180
+007181
+007182
+007183
+007184
+007185
+007186
+007187
+007188
+007189
+007190
+007191
+007192
+007193
+007194
+007195
+007196
+007197
+007198
+007199
+007200
+007201
+007202
+007203
+007204
+007205
+007206
+007207
+007208
+007209
+007210
+007211
+007212
+007213
+007214
+007215
+007216
+007217
+007218
+007219
+007220
+007221
+007222
+007223
+007224
+007225
+007226
+007227
+007228
+007229
+007230
+007231
+007232
+007233
+007234
+007235
+007236
+007237
+007238
+007239
+007240
+007241
+007242
+007243
+007244
+007245
+007246
+007247
+007248
+007249
+007250
+007251
+007252
+007253
+007254
+007255
+007256
+007257
+007258
+007259
+007260
+007261
+007262
+007263
+007264
+007265
+007266
+007267
+007268
+007269
+007270
+007271
+007272
+007273
+007274
+007275
+007276
+007277
+007278
+007279
+007280
+007281
+007282
+007283
+007284
+007285
+007286
+007287
+007288
+007289
+007290
+007291
+007292
+007293
+007294
+007295
+007296
+007297
+007298
+007299
+007300
+007301
+007302
+007303
+007304
+007305
+007306
+007307
+007308
+007309
+007310
+007311
+007312
+007313
+007314
+007315
+007316
+007317
+007318
+007319
+007320
+007321
+007322
+007323
+007324
+007325
+007326
+007327
+007328
+007329
+007330
+007331
+007332
+007333
+007334
+007335
+007336
+007337
+007338
+007339
+007340
+007341
+007342
+007343
+007344
+007345
+007346
+007347
+007348
+007349
+007350
+007351
+007352
+007353
+007354
+007355
+007356
+007357
+007358
+007359
+007360
+007361
+007362
+007363
+007364
+007365
+007366
+007367
+007368
+007369
+007370
+007371
+007372
+007373
+007374
+007375
+007376
+007377
+007378
+007379
+007380
+007381
+007382
+007383
+007384
+007385
+007386
+007387
+007388
+007389
+007390
+007391
+007392
+007393
+007394
+007395
+007396
+007397
+007398
+007399
+007400
+007401
+007402
+007403
+007404
+007405
+007406
+007407
+007408
+007409
+007410
+007411
+007412
+007413
+007414
+007415
+007416
+007417
+007418
+007419
+007420
+007421
+007422
+007423
+007424
+007425
+007426
+007427
+007428
+007429
+007430
+007431
+007432
+007433
+007434
+007435
+007436
+007437
+007438
+007439
+007440
+007441
+007442
+007443
+007444
+007445
+007446
+007447
+007448
+007449
+007450
+007451
+007452
+007453
+007454
+007455
+007456
+007457
+007458
+007459
+007460
+007461
+007462
+007463
+007464
+007465
+007466
+007467
+007468
+007469
+007470
+007471
+007472
+007473
+007474
+007475
+007476
+007477
+007478
+007479
+007480
+007481
+007482
+007483
+007484
+007485
+007486
+007487
+007488
+007489
+007490
+007491
+007492
+007493
+007494
+007495
+007496
+007497
+007498
+007499
+007500
+007501
+007502
+007503
+007504
+007505
+007506
+007507
+007508
+007509
+007510
+007511
+007512
+007513
+007514
+007515
+007516
+007517
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/train.txt b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/train.txt
new file mode 100644
index 00000000000..505b1e26668
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/train.txt
@@ -0,0 +1,3712 @@
+000000
+000003
+000007
+000009
+000010
+000011
+000012
+000013
+000014
+000016
+000017
+000018
+000022
+000026
+000029
+000030
+000032
+000034
+000036
+000038
+000041
+000043
+000044
+000045
+000046
+000049
+000051
+000054
+000055
+000056
+000057
+000060
+000064
+000067
+000068
+000069
+000070
+000071
+000072
+000073
+000074
+000075
+000079
+000080
+000082
+000083
+000084
+000085
+000086
+000087
+000088
+000091
+000092
+000095
+000096
+000097
+000099
+000100
+000101
+000103
+000105
+000109
+000110
+000111
+000112
+000113
+000114
+000115
+000119
+000120
+000121
+000123
+000125
+000127
+000129
+000130
+000131
+000133
+000136
+000138
+000141
+000142
+000144
+000145
+000146
+000148
+000149
+000150
+000154
+000155
+000157
+000158
+000160
+000162
+000163
+000164
+000165
+000166
+000171
+000172
+000176
+000177
+000178
+000179
+000180
+000184
+000185
+000189
+000193
+000198
+000200
+000202
+000205
+000206
+000208
+000209
+000210
+000214
+000215
+000217
+000219
+000220
+000221
+000222
+000225
+000227
+000228
+000232
+000233
+000238
+000240
+000241
+000243
+000244
+000245
+000253
+000254
+000255
+000256
+000257
+000258
+000259
+000261
+000264
+000267
+000271
+000274
+000275
+000276
+000277
+000280
+000282
+000285
+000286
+000287
+000288
+000292
+000294
+000295
+000296
+000298
+000299
+000300
+000303
+000304
+000306
+000310
+000313
+000316
+000317
+000318
+000322
+000325
+000326
+000330
+000331
+000334
+000337
+000338
+000339
+000342
+000344
+000348
+000349
+000353
+000358
+000363
+000364
+000367
+000368
+000371
+000374
+000375
+000380
+000384
+000387
+000389
+000390
+000400
+000405
+000406
+000410
+000411
+000412
+000416
+000417
+000418
+000421
+000423
+000424
+000425
+000426
+000431
+000432
+000433
+000434
+000435
+000438
+000439
+000441
+000442
+000444
+000445
+000447
+000449
+000456
+000458
+000460
+000461
+000462
+000464
+000465
+000466
+000467
+000470
+000471
+000474
+000482
+000483
+000484
+000487
+000488
+000490
+000497
+000500
+000501
+000502
+000505
+000507
+000511
+000513
+000514
+000516
+000518
+000520
+000522
+000523
+000525
+000526
+000529
+000531
+000532
+000534
+000535
+000537
+000538
+000539
+000540
+000544
+000547
+000549
+000550
+000552
+000553
+000556
+000557
+000562
+000563
+000565
+000570
+000573
+000574
+000575
+000576
+000577
+000578
+000579
+000580
+000582
+000584
+000585
+000586
+000587
+000592
+000593
+000594
+000596
+000597
+000598
+000599
+000602
+000603
+000605
+000606
+000607
+000608
+000609
+000616
+000617
+000621
+000622
+000623
+000627
+000629
+000631
+000632
+000633
+000637
+000638
+000640
+000641
+000643
+000646
+000649
+000651
+000652
+000653
+000654
+000656
+000661
+000662
+000663
+000664
+000665
+000666
+000668
+000671
+000672
+000673
+000675
+000676
+000678
+000680
+000681
+000685
+000686
+000687
+000688
+000689
+000690
+000693
+000695
+000697
+000701
+000703
+000705
+000707
+000709
+000710
+000711
+000712
+000713
+000714
+000715
+000719
+000720
+000723
+000724
+000726
+000730
+000732
+000733
+000735
+000738
+000739
+000742
+000743
+000744
+000747
+000749
+000753
+000755
+000757
+000758
+000759
+000760
+000762
+000763
+000764
+000770
+000775
+000776
+000777
+000780
+000781
+000783
+000784
+000785
+000786
+000787
+000788
+000789
+000791
+000793
+000794
+000796
+000797
+000799
+000808
+000813
+000814
+000815
+000817
+000818
+000820
+000821
+000822
+000824
+000825
+000827
+000828
+000829
+000830
+000832
+000833
+000834
+000835
+000836
+000839
+000842
+000845
+000846
+000851
+000853
+000855
+000856
+000857
+000858
+000860
+000861
+000864
+000865
+000866
+000867
+000868
+000870
+000871
+000872
+000880
+000882
+000883
+000886
+000887
+000888
+000890
+000891
+000892
+000895
+000896
+000898
+000900
+000901
+000902
+000903
+000905
+000906
+000908
+000910
+000913
+000914
+000918
+000919
+000921
+000924
+000925
+000927
+000929
+000933
+000934
+000935
+000936
+000937
+000941
+000945
+000946
+000947
+000950
+000951
+000954
+000955
+000957
+000959
+000960
+000962
+000965
+000968
+000972
+000975
+000977
+000978
+000980
+000982
+000987
+000989
+000990
+000992
+000993
+000994
+000995
+000996
+000997
+000998
+001000
+001001
+001003
+001004
+001005
+001009
+001016
+001017
+001020
+001023
+001024
+001028
+001029
+001030
+001031
+001032
+001033
+001034
+001036
+001038
+001040
+001041
+001044
+001045
+001047
+001048
+001049
+001052
+001056
+001057
+001059
+001060
+001061
+001062
+001064
+001072
+001073
+001074
+001079
+001080
+001081
+001082
+001085
+001087
+001090
+001091
+001092
+001093
+001098
+001100
+001103
+001105
+001109
+001110
+001112
+001117
+001119
+001121
+001122
+001124
+001126
+001128
+001130
+001137
+001142
+001146
+001151
+001156
+001157
+001159
+001160
+001161
+001164
+001165
+001166
+001168
+001169
+001170
+001171
+001174
+001175
+001181
+001184
+001185
+001186
+001190
+001196
+001197
+001200
+001201
+001202
+001204
+001205
+001208
+001209
+001210
+001211
+001212
+001215
+001219
+001220
+001223
+001227
+001229
+001231
+001233
+001238
+001240
+001247
+001248
+001250
+001256
+001258
+001262
+001264
+001276
+001277
+001278
+001279
+001280
+001282
+001283
+001285
+001288
+001290
+001293
+001297
+001298
+001299
+001300
+001301
+001302
+001309
+001310
+001311
+001312
+001313
+001315
+001316
+001319
+001320
+001321
+001322
+001323
+001324
+001325
+001326
+001327
+001328
+001335
+001338
+001340
+001341
+001343
+001348
+001349
+001351
+001354
+001357
+001358
+001360
+001361
+001362
+001364
+001366
+001367
+001368
+001369
+001370
+001371
+001373
+001378
+001379
+001383
+001385
+001390
+001392
+001393
+001394
+001396
+001399
+001400
+001401
+001402
+001403
+001404
+001405
+001406
+001408
+001409
+001413
+001414
+001417
+001418
+001420
+001422
+001423
+001425
+001426
+001428
+001429
+001430
+001433
+001434
+001436
+001440
+001444
+001447
+001449
+001452
+001453
+001454
+001455
+001456
+001457
+001459
+001460
+001462
+001464
+001465
+001467
+001468
+001470
+001472
+001473
+001474
+001475
+001476
+001479
+001482
+001483
+001484
+001486
+001490
+001491
+001492
+001493
+001494
+001496
+001498
+001499
+001500
+001503
+001504
+001505
+001506
+001509
+001510
+001512
+001515
+001518
+001519
+001520
+001523
+001529
+001530
+001531
+001532
+001534
+001539
+001540
+001541
+001543
+001544
+001548
+001550
+001551
+001553
+001554
+001556
+001558
+001559
+001561
+001563
+001566
+001568
+001570
+001571
+001572
+001575
+001578
+001580
+001581
+001584
+001593
+001595
+001598
+001599
+001601
+001604
+001607
+001608
+001609
+001611
+001612
+001614
+001618
+001620
+001622
+001623
+001624
+001626
+001628
+001630
+001632
+001636
+001637
+001638
+001639
+001641
+001642
+001644
+001646
+001648
+001649
+001651
+001652
+001653
+001655
+001657
+001659
+001661
+001663
+001668
+001669
+001671
+001672
+001673
+001674
+001676
+001677
+001678
+001679
+001681
+001685
+001686
+001687
+001688
+001690
+001691
+001692
+001695
+001696
+001698
+001700
+001703
+001708
+001715
+001716
+001720
+001723
+001724
+001725
+001728
+001730
+001731
+001734
+001735
+001736
+001737
+001738
+001739
+001743
+001744
+001747
+001748
+001753
+001754
+001756
+001757
+001759
+001760
+001761
+001763
+001766
+001767
+001769
+001770
+001773
+001775
+001777
+001779
+001784
+001785
+001788
+001789
+001790
+001791
+001792
+001793
+001796
+001798
+001799
+001803
+001805
+001806
+001809
+001810
+001811
+001812
+001815
+001816
+001819
+001821
+001826
+001827
+001829
+001830
+001832
+001833
+001834
+001836
+001837
+001838
+001839
+001841
+001842
+001843
+001845
+001847
+001849
+001850
+001857
+001860
+001864
+001865
+001866
+001870
+001871
+001873
+001874
+001876
+001879
+001882
+001883
+001889
+001891
+001894
+001895
+001896
+001899
+001901
+001902
+001903
+001906
+001907
+001908
+001910
+001911
+001912
+001913
+001914
+001915
+001916
+001917
+001918
+001921
+001922
+001930
+001935
+001938
+001939
+001944
+001947
+001948
+001949
+001950
+001951
+001953
+001955
+001956
+001957
+001958
+001961
+001962
+001963
+001964
+001965
+001968
+001970
+001971
+001973
+001974
+001975
+001976
+001981
+001987
+001988
+001990
+001992
+001993
+001994
+001998
+002003
+002005
+002006
+002007
+002009
+002015
+002016
+002018
+002020
+002023
+002024
+002026
+002030
+002031
+002032
+002033
+002039
+002040
+002041
+002047
+002051
+002053
+002055
+002059
+002060
+002061
+002063
+002064
+002065
+002066
+002067
+002069
+002070
+002072
+002077
+002080
+002083
+002084
+002088
+002090
+002092
+002095
+002096
+002097
+002098
+002099
+002104
+002105
+002106
+002109
+002110
+002114
+002116
+002117
+002119
+002122
+002125
+002126
+002129
+002132
+002133
+002134
+002141
+002143
+002144
+002145
+002146
+002147
+002148
+002149
+002150
+002154
+002155
+002156
+002157
+002162
+002164
+002167
+002171
+002172
+002174
+002175
+002176
+002178
+002180
+002181
+002184
+002186
+002189
+002190
+002191
+002192
+002194
+002195
+002197
+002198
+002199
+002203
+002204
+002205
+002208
+002210
+002211
+002212
+002213
+002214
+002217
+002221
+002222
+002223
+002226
+002227
+002230
+002231
+002235
+002236
+002237
+002238
+002240
+002241
+002242
+002244
+002247
+002249
+002252
+002253
+002256
+002259
+002261
+002263
+002264
+002265
+002267
+002268
+002269
+002270
+002271
+002273
+002274
+002275
+002278
+002281
+002285
+002288
+002289
+002296
+002297
+002301
+002302
+002305
+002309
+002311
+002312
+002313
+002316
+002317
+002318
+002321
+002322
+002323
+002324
+002326
+002328
+002331
+002333
+002335
+002339
+002342
+002343
+002349
+002350
+002351
+002352
+002354
+002355
+002358
+002360
+002361
+002363
+002364
+002368
+002371
+002373
+002374
+002375
+002377
+002379
+002381
+002388
+002389
+002390
+002394
+002395
+002396
+002400
+002401
+002402
+002403
+002406
+002407
+002408
+002409
+002410
+002412
+002413
+002416
+002417
+002421
+002426
+002427
+002430
+002431
+002435
+002436
+002437
+002438
+002441
+002443
+002444
+002445
+002447
+002448
+002449
+002451
+002452
+002453
+002456
+002459
+002464
+002465
+002466
+002467
+002468
+002469
+002470
+002471
+002472
+002475
+002480
+002481
+002482
+002484
+002485
+002487
+002489
+002491
+002493
+002494
+002496
+002498
+002501
+002507
+002508
+002510
+002512
+002513
+002514
+002515
+002517
+002518
+002522
+002523
+002524
+002527
+002533
+002535
+002536
+002537
+002542
+002544
+002545
+002547
+002549
+002550
+002551
+002553
+002554
+002555
+002559
+002560
+002561
+002566
+002567
+002571
+002573
+002576
+002578
+002579
+002582
+002587
+002588
+002589
+002591
+002592
+002593
+002595
+002596
+002597
+002605
+002607
+002608
+002609
+002610
+002611
+002614
+002616
+002617
+002618
+002620
+002622
+002623
+002624
+002627
+002629
+002632
+002634
+002637
+002639
+002642
+002643
+002647
+002648
+002649
+002650
+002652
+002654
+002655
+002658
+002659
+002660
+002662
+002664
+002665
+002667
+002668
+002670
+002671
+002672
+002676
+002678
+002679
+002682
+002683
+002684
+002687
+002688
+002689
+002691
+002697
+002698
+002700
+002701
+002703
+002704
+002705
+002708
+002714
+002716
+002718
+002719
+002723
+002731
+002732
+002733
+002734
+002736
+002738
+002739
+002741
+002743
+002750
+002751
+002754
+002756
+002759
+002762
+002766
+002768
+002769
+002770
+002771
+002774
+002776
+002777
+002778
+002779
+002780
+002781
+002782
+002784
+002785
+002788
+002790
+002791
+002792
+002795
+002798
+002799
+002802
+002803
+002807
+002808
+002813
+002816
+002817
+002819
+002821
+002822
+002823
+002824
+002825
+002829
+002832
+002834
+002835
+002837
+002838
+002842
+002843
+002849
+002850
+002851
+002852
+002854
+002855
+002857
+002859
+002860
+002862
+002864
+002865
+002868
+002869
+002870
+002871
+002872
+002873
+002874
+002882
+002884
+002886
+002887
+002888
+002897
+002898
+002899
+002904
+002906
+002907
+002909
+002910
+002912
+002913
+002915
+002918
+002920
+002921
+002922
+002923
+002926
+002927
+002929
+002931
+002932
+002933
+002936
+002938
+002939
+002940
+002941
+002943
+002946
+002949
+002950
+002952
+002954
+002956
+002965
+002967
+002968
+002969
+002970
+002972
+002973
+002975
+002980
+002981
+002983
+002986
+002987
+002989
+002990
+002992
+002996
+002998
+003002
+003008
+003009
+003012
+003013
+003014
+003015
+003016
+003017
+003018
+003020
+003021
+003023
+003026
+003028
+003036
+003037
+003039
+003040
+003041
+003044
+003045
+003049
+003051
+003057
+003059
+003060
+003063
+003064
+003068
+003069
+003070
+003072
+003075
+003077
+003078
+003079
+003081
+003083
+003084
+003085
+003086
+003089
+003091
+003092
+003093
+003095
+003097
+003098
+003100
+003104
+003105
+003108
+003111
+003113
+003115
+003117
+003119
+003120
+003121
+003122
+003123
+003125
+003128
+003130
+003132
+003138
+003139
+003140
+003143
+003147
+003149
+003151
+003152
+003154
+003155
+003157
+003158
+003160
+003163
+003164
+003166
+003168
+003169
+003171
+003173
+003176
+003178
+003184
+003185
+003186
+003188
+003189
+003191
+003193
+003195
+003196
+003198
+003200
+003201
+003205
+003206
+003208
+003209
+003212
+003213
+003215
+003218
+003220
+003223
+003227
+003230
+003234
+003235
+003237
+003238
+003241
+003243
+003244
+003245
+003246
+003248
+003249
+003253
+003256
+003258
+003260
+003261
+003262
+003263
+003264
+003267
+003268
+003270
+003271
+003273
+003274
+003277
+003278
+003279
+003282
+003284
+003285
+003286
+003287
+003289
+003290
+003291
+003293
+003294
+003297
+003299
+003303
+003307
+003309
+003311
+003314
+003317
+003320
+003321
+003326
+003327
+003328
+003329
+003332
+003333
+003334
+003335
+003336
+003339
+003340
+003342
+003344
+003345
+003348
+003349
+003354
+003356
+003359
+003360
+003361
+003362
+003363
+003369
+003371
+003372
+003374
+003376
+003377
+003378
+003380
+003381
+003382
+003383
+003384
+003387
+003388
+003389
+003390
+003391
+003392
+003398
+003400
+003413
+003414
+003415
+003416
+003418
+003420
+003423
+003424
+003427
+003431
+003433
+003436
+003437
+003438
+003439
+003440
+003441
+003442
+003444
+003445
+003446
+003451
+003452
+003454
+003455
+003457
+003458
+003459
+003460
+003462
+003463
+003468
+003472
+003473
+003475
+003476
+003477
+003479
+003485
+003486
+003493
+003494
+003498
+003499
+003500
+003501
+003505
+003507
+003508
+003509
+003510
+003512
+003513
+003514
+003516
+003518
+003522
+003523
+003525
+003526
+003532
+003533
+003534
+003536
+003537
+003538
+003540
+003541
+003542
+003545
+003546
+003548
+003549
+003551
+003555
+003556
+003560
+003561
+003564
+003565
+003566
+003567
+003569
+003570
+003572
+003575
+003576
+003577
+003578
+003579
+003581
+003585
+003586
+003587
+003589
+003590
+003591
+003592
+003593
+003594
+003595
+003596
+003597
+003598
+003599
+003602
+003603
+003606
+003610
+003612
+003613
+003615
+003617
+003619
+003625
+003626
+003628
+003636
+003637
+003638
+003639
+003640
+003641
+003642
+003644
+003646
+003648
+003650
+003651
+003654
+003656
+003657
+003660
+003663
+003664
+003665
+003666
+003670
+003672
+003673
+003674
+003675
+003680
+003681
+003685
+003686
+003687
+003693
+003694
+003695
+003696
+003697
+003698
+003699
+003700
+003701
+003704
+003706
+003709
+003710
+003713
+003714
+003717
+003720
+003721
+003722
+003724
+003725
+003727
+003729
+003730
+003731
+003732
+003733
+003734
+003740
+003741
+003742
+003743
+003744
+003745
+003749
+003752
+003754
+003757
+003758
+003759
+003760
+003761
+003765
+003766
+003767
+003768
+003770
+003772
+003773
+003774
+003776
+003780
+003783
+003784
+003785
+003786
+003789
+003790
+003791
+003792
+003795
+003796
+003797
+003799
+003801
+003803
+003806
+003810
+003813
+003815
+003816
+003817
+003818
+003819
+003821
+003823
+003824
+003825
+003829
+003831
+003832
+003833
+003836
+003838
+003839
+003840
+003842
+003843
+003844
+003845
+003846
+003848
+003849
+003850
+003851
+003853
+003855
+003857
+003858
+003861
+003862
+003863
+003865
+003867
+003868
+003871
+003875
+003876
+003877
+003882
+003884
+003887
+003888
+003889
+003893
+003895
+003896
+003900
+003903
+003904
+003906
+003908
+003910
+003911
+003912
+003913
+003917
+003918
+003919
+003921
+003922
+003925
+003927
+003928
+003929
+003930
+003933
+003935
+003936
+003939
+003940
+003941
+003942
+003944
+003947
+003949
+003951
+003952
+003953
+003954
+003955
+003957
+003959
+003960
+003963
+003966
+003967
+003968
+003971
+003973
+003974
+003976
+003978
+003979
+003983
+003985
+003987
+003988
+003989
+003990
+003991
+003993
+003994
+003995
+003997
+003999
+004005
+004006
+004012
+004013
+004014
+004015
+004017
+004018
+004019
+004020
+004022
+004023
+004024
+004025
+004029
+004030
+004031
+004035
+004037
+004039
+004043
+004044
+004046
+004047
+004050
+004052
+004053
+004054
+004056
+004057
+004058
+004060
+004062
+004066
+004067
+004069
+004070
+004071
+004073
+004075
+004076
+004078
+004080
+004084
+004086
+004088
+004090
+004093
+004094
+004097
+004099
+004102
+004103
+004106
+004112
+004114
+004115
+004123
+004127
+004133
+004134
+004135
+004139
+004141
+004144
+004145
+004146
+004147
+004151
+004159
+004165
+004166
+004167
+004169
+004170
+004176
+004177
+004178
+004179
+004180
+004181
+004182
+004183
+004184
+004186
+004192
+004193
+004194
+004197
+004198
+004199
+004200
+004201
+004203
+004204
+004208
+004211
+004212
+004216
+004217
+004218
+004219
+004225
+004227
+004229
+004230
+004231
+004233
+004234
+004235
+004236
+004238
+004240
+004244
+004245
+004247
+004252
+004253
+004257
+004258
+004261
+004262
+004264
+004265
+004266
+004267
+004268
+004269
+004272
+004273
+004274
+004276
+004279
+004283
+004286
+004287
+004292
+004296
+004297
+004302
+004304
+004308
+004310
+004313
+004315
+004316
+004317
+004320
+004322
+004325
+004328
+004331
+004332
+004333
+004334
+004339
+004341
+004344
+004346
+004347
+004351
+004354
+004355
+004356
+004357
+004358
+004359
+004361
+004365
+004366
+004371
+004372
+004375
+004376
+004378
+004379
+004380
+004381
+004382
+004386
+004387
+004389
+004390
+004394
+004395
+004399
+004400
+004405
+004408
+004409
+004410
+004411
+004412
+004413
+004416
+004417
+004427
+004428
+004431
+004432
+004436
+004441
+004442
+004445
+004446
+004448
+004449
+004451
+004453
+004455
+004457
+004459
+004461
+004463
+004464
+004466
+004467
+004468
+004471
+004473
+004476
+004477
+004478
+004479
+004484
+004488
+004492
+004495
+004497
+004498
+004499
+004500
+004503
+004504
+004505
+004506
+004507
+004509
+004510
+004512
+004514
+004515
+004518
+004522
+004523
+004524
+004525
+004533
+004535
+004536
+004537
+004538
+004539
+004543
+004544
+004545
+004546
+004550
+004552
+004554
+004555
+004558
+004559
+004560
+004561
+004563
+004564
+004565
+004571
+004572
+004575
+004577
+004579
+004580
+004583
+004584
+004586
+004590
+004592
+004593
+004594
+004595
+004597
+004600
+004601
+004602
+004604
+004605
+004606
+004607
+004613
+004614
+004616
+004617
+004619
+004621
+004623
+004625
+004627
+004628
+004631
+004635
+004637
+004639
+004641
+004642
+004643
+004645
+004646
+004653
+004654
+004656
+004659
+004661
+004662
+004663
+004664
+004670
+004671
+004674
+004675
+004676
+004677
+004678
+004681
+004684
+004690
+004696
+004701
+004702
+004703
+004704
+004707
+004712
+004719
+004723
+004727
+004728
+004729
+004731
+004733
+004736
+004741
+004747
+004749
+004750
+004751
+004754
+004755
+004757
+004758
+004760
+004761
+004765
+004767
+004771
+004772
+004774
+004775
+004778
+004779
+004780
+004781
+004784
+004785
+004786
+004789
+004793
+004794
+004795
+004796
+004798
+004801
+004802
+004803
+004805
+004808
+004809
+004812
+004818
+004819
+004820
+004823
+004824
+004826
+004827
+004828
+004833
+004834
+004836
+004837
+004838
+004840
+004841
+004842
+004844
+004845
+004847
+004853
+004854
+004855
+004856
+004857
+004865
+004866
+004869
+004870
+004872
+004876
+004877
+004878
+004879
+004880
+004882
+004883
+004884
+004886
+004889
+004890
+004894
+004897
+004899
+004900
+004901
+004906
+004908
+004910
+004911
+004912
+004913
+004915
+004916
+004919
+004922
+004923
+004925
+004930
+004933
+004936
+004937
+004939
+004940
+004945
+004950
+004951
+004952
+004955
+004957
+004961
+004964
+004965
+004967
+004968
+004969
+004970
+004971
+004972
+004973
+004975
+004977
+004978
+004980
+004982
+004984
+004987
+004991
+004992
+004997
+005000
+005003
+005005
+005006
+005007
+005009
+005011
+005012
+005016
+005018
+005020
+005022
+005023
+005025
+005027
+005029
+005030
+005031
+005033
+005035
+005039
+005042
+005043
+005044
+005046
+005047
+005048
+005051
+005059
+005060
+005061
+005066
+005069
+005071
+005076
+005083
+005084
+005085
+005087
+005088
+005089
+005091
+005092
+005096
+005097
+005098
+005099
+005100
+005102
+005104
+005106
+005107
+005111
+005114
+005115
+005116
+005117
+005118
+005119
+005123
+005126
+005129
+005130
+005131
+005132
+005134
+005137
+005142
+005146
+005148
+005150
+005151
+005152
+005154
+005159
+005160
+005165
+005169
+005171
+005173
+005177
+005178
+005183
+005186
+005187
+005192
+005193
+005195
+005196
+005200
+005202
+005203
+005204
+005205
+005207
+005208
+005209
+005210
+005211
+005212
+005215
+005216
+005220
+005223
+005224
+005225
+005228
+005231
+005232
+005235
+005238
+005239
+005243
+005245
+005247
+005248
+005250
+005252
+005253
+005254
+005257
+005258
+005259
+005261
+005263
+005264
+005265
+005266
+005269
+005270
+005272
+005277
+005278
+005281
+005283
+005285
+005286
+005288
+005290
+005291
+005293
+005294
+005295
+005300
+005301
+005302
+005303
+005305
+005306
+005310
+005314
+005317
+005320
+005324
+005326
+005327
+005331
+005332
+005339
+005340
+005344
+005346
+005348
+005351
+005352
+005353
+005354
+005355
+005356
+005357
+005358
+005361
+005362
+005364
+005367
+005370
+005373
+005374
+005376
+005380
+005382
+005383
+005384
+005387
+005388
+005392
+005393
+005394
+005395
+005396
+005397
+005398
+005399
+005400
+005401
+005402
+005403
+005406
+005407
+005408
+005409
+005410
+005411
+005412
+005414
+005416
+005417
+005418
+005419
+005420
+005421
+005424
+005425
+005428
+005432
+005433
+005435
+005436
+005438
+005439
+005440
+005442
+005446
+005451
+005454
+005455
+005456
+005457
+005462
+005463
+005464
+005468
+005469
+005470
+005475
+005478
+005480
+005483
+005485
+005488
+005490
+005491
+005492
+005493
+005496
+005497
+005499
+005500
+005501
+005502
+005503
+005504
+005506
+005507
+005508
+005509
+005512
+005513
+005516
+005517
+005518
+005519
+005520
+005521
+005522
+005524
+005526
+005527
+005529
+005530
+005533
+005535
+005537
+005539
+005541
+005543
+005547
+005548
+005549
+005550
+005553
+005554
+005561
+005562
+005563
+005564
+005567
+005568
+005569
+005574
+005575
+005578
+005579
+005583
+005585
+005591
+005592
+005593
+005594
+005597
+005598
+005599
+005604
+005605
+005606
+005607
+005608
+005609
+005611
+005612
+005614
+005615
+005620
+005621
+005622
+005624
+005626
+005627
+005628
+005629
+005632
+005636
+005637
+005641
+005644
+005645
+005646
+005647
+005648
+005651
+005654
+005655
+005657
+005661
+005663
+005665
+005666
+005667
+005670
+005671
+005674
+005675
+005678
+005679
+005681
+005682
+005684
+005686
+005688
+005690
+005691
+005692
+005693
+005694
+005696
+005697
+005701
+005702
+005705
+005710
+005711
+005715
+005716
+005718
+005719
+005720
+005721
+005722
+005723
+005726
+005730
+005732
+005733
+005734
+005737
+005738
+005742
+005748
+005749
+005750
+005752
+005753
+005755
+005756
+005758
+005759
+005761
+005764
+005766
+005767
+005768
+005769
+005770
+005771
+005772
+005773
+005774
+005775
+005776
+005778
+005779
+005780
+005781
+005788
+005789
+005791
+005792
+005795
+005797
+005798
+005799
+005802
+005804
+005808
+005809
+005810
+005813
+005814
+005815
+005816
+005817
+005823
+005824
+005825
+005828
+005830
+005831
+005832
+005833
+005835
+005836
+005837
+005838
+005842
+005844
+005845
+005846
+005847
+005848
+005849
+005850
+005851
+005853
+005858
+005860
+005861
+005862
+005863
+005865
+005866
+005867
+005868
+005870
+005871
+005872
+005874
+005875
+005877
+005880
+005884
+005886
+005888
+005890
+005891
+005895
+005896
+005897
+005898
+005902
+005904
+005908
+005915
+005920
+005924
+005928
+005929
+005930
+005932
+005934
+005936
+005937
+005940
+005941
+005942
+005943
+005945
+005946
+005950
+005951
+005953
+005954
+005956
+005957
+005959
+005960
+005964
+005966
+005967
+005968
+005971
+005973
+005974
+005976
+005977
+005979
+005980
+005983
+005987
+005989
+005990
+005991
+005992
+005993
+005995
+005998
+006000
+006004
+006006
+006007
+006011
+006015
+006017
+006018
+006019
+006020
+006021
+006022
+006025
+006032
+006035
+006037
+006040
+006049
+006051
+006053
+006055
+006056
+006059
+006064
+006065
+006069
+006072
+006073
+006076
+006079
+006080
+006081
+006082
+006084
+006089
+006090
+006091
+006092
+006094
+006099
+006101
+006104
+006105
+006108
+006109
+006111
+006112
+006113
+006119
+006120
+006124
+006128
+006129
+006131
+006132
+006134
+006135
+006137
+006138
+006140
+006141
+006142
+006143
+006145
+006147
+006149
+006150
+006153
+006155
+006157
+006158
+006159
+006160
+006162
+006164
+006166
+006170
+006171
+006172
+006174
+006175
+006178
+006179
+006180
+006181
+006183
+006184
+006188
+006189
+006191
+006192
+006193
+006197
+006199
+006200
+006201
+006203
+006205
+006206
+006207
+006209
+006211
+006212
+006214
+006216
+006217
+006218
+006220
+006221
+006223
+006224
+006225
+006226
+006230
+006231
+006234
+006235
+006236
+006237
+006239
+006241
+006242
+006243
+006245
+006248
+006251
+006252
+006253
+006254
+006255
+006256
+006257
+006259
+006260
+006261
+006262
+006264
+006268
+006271
+006277
+006279
+006281
+006283
+006284
+006285
+006289
+006290
+006291
+006292
+006293
+006294
+006295
+006296
+006298
+006299
+006303
+006304
+006307
+006308
+006309
+006310
+006311
+006313
+006318
+006319
+006320
+006323
+006325
+006326
+006327
+006328
+006329
+006330
+006335
+006336
+006337
+006341
+006346
+006347
+006350
+006352
+006358
+006359
+006361
+006362
+006363
+006365
+006367
+006373
+006374
+006375
+006376
+006378
+006382
+006383
+006384
+006387
+006389
+006390
+006392
+006397
+006398
+006399
+006400
+006401
+006402
+006404
+006408
+006412
+006413
+006414
+006418
+006419
+006421
+006422
+006428
+006429
+006430
+006431
+006432
+006438
+006443
+006447
+006448
+006449
+006450
+006455
+006456
+006457
+006458
+006459
+006460
+006461
+006463
+006466
+006467
+006471
+006476
+006479
+006480
+006485
+006487
+006489
+006490
+006492
+006494
+006495
+006499
+006500
+006501
+006502
+006504
+006509
+006510
+006511
+006513
+006518
+006522
+006523
+006526
+006527
+006528
+006536
+006538
+006539
+006541
+006543
+006544
+006545
+006546
+006547
+006550
+006552
+006554
+006557
+006559
+006562
+006564
+006566
+006567
+006571
+006572
+006573
+006575
+006579
+006580
+006584
+006585
+006587
+006589
+006591
+006594
+006598
+006599
+006600
+006601
+006605
+006606
+006607
+006608
+006609
+006610
+006615
+006616
+006617
+006619
+006620
+006621
+006622
+006627
+006630
+006631
+006635
+006639
+006640
+006642
+006644
+006645
+006646
+006648
+006652
+006653
+006654
+006657
+006661
+006662
+006663
+006665
+006668
+006671
+006672
+006673
+006675
+006680
+006681
+006683
+006684
+006687
+006688
+006689
+006690
+006691
+006697
+006699
+006700
+006702
+006704
+006705
+006706
+006707
+006708
+006716
+006717
+006718
+006721
+006722
+006724
+006727
+006728
+006730
+006735
+006736
+006739
+006740
+006742
+006743
+006746
+006748
+006749
+006750
+006757
+006763
+006766
+006769
+006774
+006775
+006776
+006779
+006784
+006787
+006788
+006790
+006793
+006795
+006799
+006801
+006802
+006805
+006809
+006810
+006814
+006817
+006820
+006821
+006823
+006824
+006825
+006826
+006827
+006830
+006831
+006834
+006835
+006838
+006839
+006840
+006842
+006845
+006846
+006848
+006851
+006857
+006859
+006861
+006864
+006865
+006867
+006869
+006871
+006875
+006877
+006878
+006880
+006883
+006886
+006888
+006890
+006892
+006893
+006894
+006896
+006902
+006904
+006905
+006909
+006911
+006912
+006915
+006916
+006918
+006919
+006920
+006921
+006923
+006924
+006926
+006927
+006929
+006931
+006932
+006933
+006934
+006935
+006939
+006940
+006941
+006946
+006947
+006949
+006951
+006952
+006957
+006958
+006961
+006963
+006965
+006966
+006967
+006969
+006970
+006972
+006974
+006975
+006976
+006979
+006983
+006984
+006985
+006986
+006988
+006991
+006993
+006995
+006996
+006998
+007001
+007002
+007004
+007007
+007009
+007013
+007017
+007018
+007020
+007021
+007024
+007025
+007035
+007036
+007039
+007040
+007041
+007044
+007045
+007046
+007050
+007051
+007054
+007057
+007058
+007060
+007062
+007064
+007066
+007070
+007073
+007075
+007077
+007086
+007090
+007092
+007093
+007094
+007096
+007097
+007099
+007101
+007102
+007104
+007105
+007106
+007107
+007108
+007111
+007113
+007114
+007116
+007118
+007121
+007123
+007124
+007126
+007127
+007128
+007129
+007134
+007137
+007140
+007141
+007142
+007143
+007147
+007148
+007150
+007151
+007152
+007153
+007155
+007156
+007159
+007160
+007167
+007170
+007171
+007173
+007175
+007179
+007181
+007184
+007185
+007186
+007188
+007189
+007190
+007191
+007192
+007193
+007195
+007196
+007197
+007203
+007206
+007209
+007211
+007213
+007216
+007218
+007220
+007222
+007223
+007224
+007226
+007228
+007231
+007234
+007236
+007237
+007239
+007241
+007243
+007245
+007248
+007249
+007250
+007251
+007254
+007257
+007259
+007263
+007264
+007268
+007269
+007270
+007276
+007281
+007282
+007285
+007286
+007293
+007295
+007296
+007297
+007298
+007301
+007305
+007306
+007307
+007308
+007312
+007313
+007314
+007316
+007317
+007320
+007321
+007324
+007328
+007332
+007333
+007334
+007335
+007338
+007340
+007341
+007346
+007348
+007354
+007355
+007356
+007357
+007358
+007361
+007362
+007363
+007365
+007366
+007367
+007368
+007370
+007372
+007373
+007378
+007379
+007386
+007387
+007388
+007390
+007392
+007393
+007394
+007399
+007400
+007404
+007406
+007408
+007414
+007417
+007418
+007425
+007427
+007428
+007429
+007431
+007432
+007438
+007441
+007443
+007444
+007446
+007451
+007452
+007454
+007455
+007457
+007459
+007460
+007461
+007465
+007471
+007472
+007474
+007476
+007479
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/trainval.txt b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/trainval.txt
new file mode 100644
index 00000000000..43467b517a7
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/trainval.txt
@@ -0,0 +1,7481 @@
+000000
+000001
+000002
+000003
+000004
+000005
+000006
+000007
+000008
+000009
+000010
+000011
+000012
+000013
+000014
+000015
+000016
+000017
+000018
+000019
+000020
+000021
+000022
+000023
+000024
+000025
+000026
+000027
+000028
+000029
+000030
+000031
+000032
+000033
+000034
+000035
+000036
+000037
+000038
+000039
+000040
+000041
+000042
+000043
+000044
+000045
+000046
+000047
+000048
+000049
+000050
+000051
+000052
+000053
+000054
+000055
+000056
+000057
+000058
+000059
+000060
+000061
+000062
+000063
+000064
+000065
+000066
+000067
+000068
+000069
+000070
+000071
+000072
+000073
+000074
+000075
+000076
+000077
+000078
+000079
+000080
+000081
+000082
+000083
+000084
+000085
+000086
+000087
+000088
+000089
+000090
+000091
+000092
+000093
+000094
+000095
+000096
+000097
+000098
+000099
+000100
+000101
+000102
+000103
+000104
+000105
+000106
+000107
+000108
+000109
+000110
+000111
+000112
+000113
+000114
+000115
+000116
+000117
+000118
+000119
+000120
+000121
+000122
+000123
+000124
+000125
+000126
+000127
+000128
+000129
+000130
+000131
+000132
+000133
+000134
+000135
+000136
+000137
+000138
+000139
+000140
+000141
+000142
+000143
+000144
+000145
+000146
+000147
+000148
+000149
+000150
+000151
+000152
+000153
+000154
+000155
+000156
+000157
+000158
+000159
+000160
+000161
+000162
+000163
+000164
+000165
+000166
+000167
+000168
+000169
+000170
+000171
+000172
+000173
+000174
+000175
+000176
+000177
+000178
+000179
+000180
+000181
+000182
+000183
+000184
+000185
+000186
+000187
+000188
+000189
+000190
+000191
+000192
+000193
+000194
+000195
+000196
+000197
+000198
+000199
+000200
+000201
+000202
+000203
+000204
+000205
+000206
+000207
+000208
+000209
+000210
+000211
+000212
+000213
+000214
+000215
+000216
+000217
+000218
+000219
+000220
+000221
+000222
+000223
+000224
+000225
+000226
+000227
+000228
+000229
+000230
+000231
+000232
+000233
+000234
+000235
+000236
+000237
+000238
+000239
+000240
+000241
+000242
+000243
+000244
+000245
+000246
+000247
+000248
+000249
+000250
+000251
+000252
+000253
+000254
+000255
+000256
+000257
+000258
+000259
+000260
+000261
+000262
+000263
+000264
+000265
+000266
+000267
+000268
+000269
+000270
+000271
+000272
+000273
+000274
+000275
+000276
+000277
+000278
+000279
+000280
+000281
+000282
+000283
+000284
+000285
+000286
+000287
+000288
+000289
+000290
+000291
+000292
+000293
+000294
+000295
+000296
+000297
+000298
+000299
+000300
+000301
+000302
+000303
+000304
+000305
+000306
+000307
+000308
+000309
+000310
+000311
+000312
+000313
+000314
+000315
+000316
+000317
+000318
+000319
+000320
+000321
+000322
+000323
+000324
+000325
+000326
+000327
+000328
+000329
+000330
+000331
+000332
+000333
+000334
+000335
+000336
+000337
+000338
+000339
+000340
+000341
+000342
+000343
+000344
+000345
+000346
+000347
+000348
+000349
+000350
+000351
+000352
+000353
+000354
+000355
+000356
+000357
+000358
+000359
+000360
+000361
+000362
+000363
+000364
+000365
+000366
+000367
+000368
+000369
+000370
+000371
+000372
+000373
+000374
+000375
+000376
+000377
+000378
+000379
+000380
+000381
+000382
+000383
+000384
+000385
+000386
+000387
+000388
+000389
+000390
+000391
+000392
+000393
+000394
+000395
+000396
+000397
+000398
+000399
+000400
+000401
+000402
+000403
+000404
+000405
+000406
+000407
+000408
+000409
+000410
+000411
+000412
+000413
+000414
+000415
+000416
+000417
+000418
+000419
+000420
+000421
+000422
+000423
+000424
+000425
+000426
+000427
+000428
+000429
+000430
+000431
+000432
+000433
+000434
+000435
+000436
+000437
+000438
+000439
+000440
+000441
+000442
+000443
+000444
+000445
+000446
+000447
+000448
+000449
+000450
+000451
+000452
+000453
+000454
+000455
+000456
+000457
+000458
+000459
+000460
+000461
+000462
+000463
+000464
+000465
+000466
+000467
+000468
+000469
+000470
+000471
+000472
+000473
+000474
+000475
+000476
+000477
+000478
+000479
+000480
+000481
+000482
+000483
+000484
+000485
+000486
+000487
+000488
+000489
+000490
+000491
+000492
+000493
+000494
+000495
+000496
+000497
+000498
+000499
+000500
+000501
+000502
+000503
+000504
+000505
+000506
+000507
+000508
+000509
+000510
+000511
+000512
+000513
+000514
+000515
+000516
+000517
+000518
+000519
+000520
+000521
+000522
+000523
+000524
+000525
+000526
+000527
+000528
+000529
+000530
+000531
+000532
+000533
+000534
+000535
+000536
+000537
+000538
+000539
+000540
+000541
+000542
+000543
+000544
+000545
+000546
+000547
+000548
+000549
+000550
+000551
+000552
+000553
+000554
+000555
+000556
+000557
+000558
+000559
+000560
+000561
+000562
+000563
+000564
+000565
+000566
+000567
+000568
+000569
+000570
+000571
+000572
+000573
+000574
+000575
+000576
+000577
+000578
+000579
+000580
+000581
+000582
+000583
+000584
+000585
+000586
+000587
+000588
+000589
+000590
+000591
+000592
+000593
+000594
+000595
+000596
+000597
+000598
+000599
+000600
+000601
+000602
+000603
+000604
+000605
+000606
+000607
+000608
+000609
+000610
+000611
+000612
+000613
+000614
+000615
+000616
+000617
+000618
+000619
+000620
+000621
+000622
+000623
+000624
+000625
+000626
+000627
+000628
+000629
+000630
+000631
+000632
+000633
+000634
+000635
+000636
+000637
+000638
+000639
+000640
+000641
+000642
+000643
+000644
+000645
+000646
+000647
+000648
+000649
+000650
+000651
+000652
+000653
+000654
+000655
+000656
+000657
+000658
+000659
+000660
+000661
+000662
+000663
+000664
+000665
+000666
+000667
+000668
+000669
+000670
+000671
+000672
+000673
+000674
+000675
+000676
+000677
+000678
+000679
+000680
+000681
+000682
+000683
+000684
+000685
+000686
+000687
+000688
+000689
+000690
+000691
+000692
+000693
+000694
+000695
+000696
+000697
+000698
+000699
+000700
+000701
+000702
+000703
+000704
+000705
+000706
+000707
+000708
+000709
+000710
+000711
+000712
+000713
+000714
+000715
+000716
+000717
+000718
+000719
+000720
+000721
+000722
+000723
+000724
+000725
+000726
+000727
+000728
+000729
+000730
+000731
+000732
+000733
+000734
+000735
+000736
+000737
+000738
+000739
+000740
+000741
+000742
+000743
+000744
+000745
+000746
+000747
+000748
+000749
+000750
+000751
+000752
+000753
+000754
+000755
+000756
+000757
+000758
+000759
+000760
+000761
+000762
+000763
+000764
+000765
+000766
+000767
+000768
+000769
+000770
+000771
+000772
+000773
+000774
+000775
+000776
+000777
+000778
+000779
+000780
+000781
+000782
+000783
+000784
+000785
+000786
+000787
+000788
+000789
+000790
+000791
+000792
+000793
+000794
+000795
+000796
+000797
+000798
+000799
+000800
+000801
+000802
+000803
+000804
+000805
+000806
+000807
+000808
+000809
+000810
+000811
+000812
+000813
+000814
+000815
+000816
+000817
+000818
+000819
+000820
+000821
+000822
+000823
+000824
+000825
+000826
+000827
+000828
+000829
+000830
+000831
+000832
+000833
+000834
+000835
+000836
+000837
+000838
+000839
+000840
+000841
+000842
+000843
+000844
+000845
+000846
+000847
+000848
+000849
+000850
+000851
+000852
+000853
+000854
+000855
+000856
+000857
+000858
+000859
+000860
+000861
+000862
+000863
+000864
+000865
+000866
+000867
+000868
+000869
+000870
+000871
+000872
+000873
+000874
+000875
+000876
+000877
+000878
+000879
+000880
+000881
+000882
+000883
+000884
+000885
+000886
+000887
+000888
+000889
+000890
+000891
+000892
+000893
+000894
+000895
+000896
+000897
+000898
+000899
+000900
+000901
+000902
+000903
+000904
+000905
+000906
+000907
+000908
+000909
+000910
+000911
+000912
+000913
+000914
+000915
+000916
+000917
+000918
+000919
+000920
+000921
+000922
+000923
+000924
+000925
+000926
+000927
+000928
+000929
+000930
+000931
+000932
+000933
+000934
+000935
+000936
+000937
+000938
+000939
+000940
+000941
+000942
+000943
+000944
+000945
+000946
+000947
+000948
+000949
+000950
+000951
+000952
+000953
+000954
+000955
+000956
+000957
+000958
+000959
+000960
+000961
+000962
+000963
+000964
+000965
+000966
+000967
+000968
+000969
+000970
+000971
+000972
+000973
+000974
+000975
+000976
+000977
+000978
+000979
+000980
+000981
+000982
+000983
+000984
+000985
+000986
+000987
+000988
+000989
+000990
+000991
+000992
+000993
+000994
+000995
+000996
+000997
+000998
+000999
+001000
+001001
+001002
+001003
+001004
+001005
+001006
+001007
+001008
+001009
+001010
+001011
+001012
+001013
+001014
+001015
+001016
+001017
+001018
+001019
+001020
+001021
+001022
+001023
+001024
+001025
+001026
+001027
+001028
+001029
+001030
+001031
+001032
+001033
+001034
+001035
+001036
+001037
+001038
+001039
+001040
+001041
+001042
+001043
+001044
+001045
+001046
+001047
+001048
+001049
+001050
+001051
+001052
+001053
+001054
+001055
+001056
+001057
+001058
+001059
+001060
+001061
+001062
+001063
+001064
+001065
+001066
+001067
+001068
+001069
+001070
+001071
+001072
+001073
+001074
+001075
+001076
+001077
+001078
+001079
+001080
+001081
+001082
+001083
+001084
+001085
+001086
+001087
+001088
+001089
+001090
+001091
+001092
+001093
+001094
+001095
+001096
+001097
+001098
+001099
+001100
+001101
+001102
+001103
+001104
+001105
+001106
+001107
+001108
+001109
+001110
+001111
+001112
+001113
+001114
+001115
+001116
+001117
+001118
+001119
+001120
+001121
+001122
+001123
+001124
+001125
+001126
+001127
+001128
+001129
+001130
+001131
+001132
+001133
+001134
+001135
+001136
+001137
+001138
+001139
+001140
+001141
+001142
+001143
+001144
+001145
+001146
+001147
+001148
+001149
+001150
+001151
+001152
+001153
+001154
+001155
+001156
+001157
+001158
+001159
+001160
+001161
+001162
+001163
+001164
+001165
+001166
+001167
+001168
+001169
+001170
+001171
+001172
+001173
+001174
+001175
+001176
+001177
+001178
+001179
+001180
+001181
+001182
+001183
+001184
+001185
+001186
+001187
+001188
+001189
+001190
+001191
+001192
+001193
+001194
+001195
+001196
+001197
+001198
+001199
+001200
+001201
+001202
+001203
+001204
+001205
+001206
+001207
+001208
+001209
+001210
+001211
+001212
+001213
+001214
+001215
+001216
+001217
+001218
+001219
+001220
+001221
+001222
+001223
+001224
+001225
+001226
+001227
+001228
+001229
+001230
+001231
+001232
+001233
+001234
+001235
+001236
+001237
+001238
+001239
+001240
+001241
+001242
+001243
+001244
+001245
+001246
+001247
+001248
+001249
+001250
+001251
+001252
+001253
+001254
+001255
+001256
+001257
+001258
+001259
+001260
+001261
+001262
+001263
+001264
+001265
+001266
+001267
+001268
+001269
+001270
+001271
+001272
+001273
+001274
+001275
+001276
+001277
+001278
+001279
+001280
+001281
+001282
+001283
+001284
+001285
+001286
+001287
+001288
+001289
+001290
+001291
+001292
+001293
+001294
+001295
+001296
+001297
+001298
+001299
+001300
+001301
+001302
+001303
+001304
+001305
+001306
+001307
+001308
+001309
+001310
+001311
+001312
+001313
+001314
+001315
+001316
+001317
+001318
+001319
+001320
+001321
+001322
+001323
+001324
+001325
+001326
+001327
+001328
+001329
+001330
+001331
+001332
+001333
+001334
+001335
+001336
+001337
+001338
+001339
+001340
+001341
+001342
+001343
+001344
+001345
+001346
+001347
+001348
+001349
+001350
+001351
+001352
+001353
+001354
+001355
+001356
+001357
+001358
+001359
+001360
+001361
+001362
+001363
+001364
+001365
+001366
+001367
+001368
+001369
+001370
+001371
+001372
+001373
+001374
+001375
+001376
+001377
+001378
+001379
+001380
+001381
+001382
+001383
+001384
+001385
+001386
+001387
+001388
+001389
+001390
+001391
+001392
+001393
+001394
+001395
+001396
+001397
+001398
+001399
+001400
+001401
+001402
+001403
+001404
+001405
+001406
+001407
+001408
+001409
+001410
+001411
+001412
+001413
+001414
+001415
+001416
+001417
+001418
+001419
+001420
+001421
+001422
+001423
+001424
+001425
+001426
+001427
+001428
+001429
+001430
+001431
+001432
+001433
+001434
+001435
+001436
+001437
+001438
+001439
+001440
+001441
+001442
+001443
+001444
+001445
+001446
+001447
+001448
+001449
+001450
+001451
+001452
+001453
+001454
+001455
+001456
+001457
+001458
+001459
+001460
+001461
+001462
+001463
+001464
+001465
+001466
+001467
+001468
+001469
+001470
+001471
+001472
+001473
+001474
+001475
+001476
+001477
+001478
+001479
+001480
+001481
+001482
+001483
+001484
+001485
+001486
+001487
+001488
+001489
+001490
+001491
+001492
+001493
+001494
+001495
+001496
+001497
+001498
+001499
+001500
+001501
+001502
+001503
+001504
+001505
+001506
+001507
+001508
+001509
+001510
+001511
+001512
+001513
+001514
+001515
+001516
+001517
+001518
+001519
+001520
+001521
+001522
+001523
+001524
+001525
+001526
+001527
+001528
+001529
+001530
+001531
+001532
+001533
+001534
+001535
+001536
+001537
+001538
+001539
+001540
+001541
+001542
+001543
+001544
+001545
+001546
+001547
+001548
+001549
+001550
+001551
+001552
+001553
+001554
+001555
+001556
+001557
+001558
+001559
+001560
+001561
+001562
+001563
+001564
+001565
+001566
+001567
+001568
+001569
+001570
+001571
+001572
+001573
+001574
+001575
+001576
+001577
+001578
+001579
+001580
+001581
+001582
+001583
+001584
+001585
+001586
+001587
+001588
+001589
+001590
+001591
+001592
+001593
+001594
+001595
+001596
+001597
+001598
+001599
+001600
+001601
+001602
+001603
+001604
+001605
+001606
+001607
+001608
+001609
+001610
+001611
+001612
+001613
+001614
+001615
+001616
+001617
+001618
+001619
+001620
+001621
+001622
+001623
+001624
+001625
+001626
+001627
+001628
+001629
+001630
+001631
+001632
+001633
+001634
+001635
+001636
+001637
+001638
+001639
+001640
+001641
+001642
+001643
+001644
+001645
+001646
+001647
+001648
+001649
+001650
+001651
+001652
+001653
+001654
+001655
+001656
+001657
+001658
+001659
+001660
+001661
+001662
+001663
+001664
+001665
+001666
+001667
+001668
+001669
+001670
+001671
+001672
+001673
+001674
+001675
+001676
+001677
+001678
+001679
+001680
+001681
+001682
+001683
+001684
+001685
+001686
+001687
+001688
+001689
+001690
+001691
+001692
+001693
+001694
+001695
+001696
+001697
+001698
+001699
+001700
+001701
+001702
+001703
+001704
+001705
+001706
+001707
+001708
+001709
+001710
+001711
+001712
+001713
+001714
+001715
+001716
+001717
+001718
+001719
+001720
+001721
+001722
+001723
+001724
+001725
+001726
+001727
+001728
+001729
+001730
+001731
+001732
+001733
+001734
+001735
+001736
+001737
+001738
+001739
+001740
+001741
+001742
+001743
+001744
+001745
+001746
+001747
+001748
+001749
+001750
+001751
+001752
+001753
+001754
+001755
+001756
+001757
+001758
+001759
+001760
+001761
+001762
+001763
+001764
+001765
+001766
+001767
+001768
+001769
+001770
+001771
+001772
+001773
+001774
+001775
+001776
+001777
+001778
+001779
+001780
+001781
+001782
+001783
+001784
+001785
+001786
+001787
+001788
+001789
+001790
+001791
+001792
+001793
+001794
+001795
+001796
+001797
+001798
+001799
+001800
+001801
+001802
+001803
+001804
+001805
+001806
+001807
+001808
+001809
+001810
+001811
+001812
+001813
+001814
+001815
+001816
+001817
+001818
+001819
+001820
+001821
+001822
+001823
+001824
+001825
+001826
+001827
+001828
+001829
+001830
+001831
+001832
+001833
+001834
+001835
+001836
+001837
+001838
+001839
+001840
+001841
+001842
+001843
+001844
+001845
+001846
+001847
+001848
+001849
+001850
+001851
+001852
+001853
+001854
+001855
+001856
+001857
+001858
+001859
+001860
+001861
+001862
+001863
+001864
+001865
+001866
+001867
+001868
+001869
+001870
+001871
+001872
+001873
+001874
+001875
+001876
+001877
+001878
+001879
+001880
+001881
+001882
+001883
+001884
+001885
+001886
+001887
+001888
+001889
+001890
+001891
+001892
+001893
+001894
+001895
+001896
+001897
+001898
+001899
+001900
+001901
+001902
+001903
+001904
+001905
+001906
+001907
+001908
+001909
+001910
+001911
+001912
+001913
+001914
+001915
+001916
+001917
+001918
+001919
+001920
+001921
+001922
+001923
+001924
+001925
+001926
+001927
+001928
+001929
+001930
+001931
+001932
+001933
+001934
+001935
+001936
+001937
+001938
+001939
+001940
+001941
+001942
+001943
+001944
+001945
+001946
+001947
+001948
+001949
+001950
+001951
+001952
+001953
+001954
+001955
+001956
+001957
+001958
+001959
+001960
+001961
+001962
+001963
+001964
+001965
+001966
+001967
+001968
+001969
+001970
+001971
+001972
+001973
+001974
+001975
+001976
+001977
+001978
+001979
+001980
+001981
+001982
+001983
+001984
+001985
+001986
+001987
+001988
+001989
+001990
+001991
+001992
+001993
+001994
+001995
+001996
+001997
+001998
+001999
+002000
+002001
+002002
+002003
+002004
+002005
+002006
+002007
+002008
+002009
+002010
+002011
+002012
+002013
+002014
+002015
+002016
+002017
+002018
+002019
+002020
+002021
+002022
+002023
+002024
+002025
+002026
+002027
+002028
+002029
+002030
+002031
+002032
+002033
+002034
+002035
+002036
+002037
+002038
+002039
+002040
+002041
+002042
+002043
+002044
+002045
+002046
+002047
+002048
+002049
+002050
+002051
+002052
+002053
+002054
+002055
+002056
+002057
+002058
+002059
+002060
+002061
+002062
+002063
+002064
+002065
+002066
+002067
+002068
+002069
+002070
+002071
+002072
+002073
+002074
+002075
+002076
+002077
+002078
+002079
+002080
+002081
+002082
+002083
+002084
+002085
+002086
+002087
+002088
+002089
+002090
+002091
+002092
+002093
+002094
+002095
+002096
+002097
+002098
+002099
+002100
+002101
+002102
+002103
+002104
+002105
+002106
+002107
+002108
+002109
+002110
+002111
+002112
+002113
+002114
+002115
+002116
+002117
+002118
+002119
+002120
+002121
+002122
+002123
+002124
+002125
+002126
+002127
+002128
+002129
+002130
+002131
+002132
+002133
+002134
+002135
+002136
+002137
+002138
+002139
+002140
+002141
+002142
+002143
+002144
+002145
+002146
+002147
+002148
+002149
+002150
+002151
+002152
+002153
+002154
+002155
+002156
+002157
+002158
+002159
+002160
+002161
+002162
+002163
+002164
+002165
+002166
+002167
+002168
+002169
+002170
+002171
+002172
+002173
+002174
+002175
+002176
+002177
+002178
+002179
+002180
+002181
+002182
+002183
+002184
+002185
+002186
+002187
+002188
+002189
+002190
+002191
+002192
+002193
+002194
+002195
+002196
+002197
+002198
+002199
+002200
+002201
+002202
+002203
+002204
+002205
+002206
+002207
+002208
+002209
+002210
+002211
+002212
+002213
+002214
+002215
+002216
+002217
+002218
+002219
+002220
+002221
+002222
+002223
+002224
+002225
+002226
+002227
+002228
+002229
+002230
+002231
+002232
+002233
+002234
+002235
+002236
+002237
+002238
+002239
+002240
+002241
+002242
+002243
+002244
+002245
+002246
+002247
+002248
+002249
+002250
+002251
+002252
+002253
+002254
+002255
+002256
+002257
+002258
+002259
+002260
+002261
+002262
+002263
+002264
+002265
+002266
+002267
+002268
+002269
+002270
+002271
+002272
+002273
+002274
+002275
+002276
+002277
+002278
+002279
+002280
+002281
+002282
+002283
+002284
+002285
+002286
+002287
+002288
+002289
+002290
+002291
+002292
+002293
+002294
+002295
+002296
+002297
+002298
+002299
+002300
+002301
+002302
+002303
+002304
+002305
+002306
+002307
+002308
+002309
+002310
+002311
+002312
+002313
+002314
+002315
+002316
+002317
+002318
+002319
+002320
+002321
+002322
+002323
+002324
+002325
+002326
+002327
+002328
+002329
+002330
+002331
+002332
+002333
+002334
+002335
+002336
+002337
+002338
+002339
+002340
+002341
+002342
+002343
+002344
+002345
+002346
+002347
+002348
+002349
+002350
+002351
+002352
+002353
+002354
+002355
+002356
+002357
+002358
+002359
+002360
+002361
+002362
+002363
+002364
+002365
+002366
+002367
+002368
+002369
+002370
+002371
+002372
+002373
+002374
+002375
+002376
+002377
+002378
+002379
+002380
+002381
+002382
+002383
+002384
+002385
+002386
+002387
+002388
+002389
+002390
+002391
+002392
+002393
+002394
+002395
+002396
+002397
+002398
+002399
+002400
+002401
+002402
+002403
+002404
+002405
+002406
+002407
+002408
+002409
+002410
+002411
+002412
+002413
+002414
+002415
+002416
+002417
+002418
+002419
+002420
+002421
+002422
+002423
+002424
+002425
+002426
+002427
+002428
+002429
+002430
+002431
+002432
+002433
+002434
+002435
+002436
+002437
+002438
+002439
+002440
+002441
+002442
+002443
+002444
+002445
+002446
+002447
+002448
+002449
+002450
+002451
+002452
+002453
+002454
+002455
+002456
+002457
+002458
+002459
+002460
+002461
+002462
+002463
+002464
+002465
+002466
+002467
+002468
+002469
+002470
+002471
+002472
+002473
+002474
+002475
+002476
+002477
+002478
+002479
+002480
+002481
+002482
+002483
+002484
+002485
+002486
+002487
+002488
+002489
+002490
+002491
+002492
+002493
+002494
+002495
+002496
+002497
+002498
+002499
+002500
+002501
+002502
+002503
+002504
+002505
+002506
+002507
+002508
+002509
+002510
+002511
+002512
+002513
+002514
+002515
+002516
+002517
+002518
+002519
+002520
+002521
+002522
+002523
+002524
+002525
+002526
+002527
+002528
+002529
+002530
+002531
+002532
+002533
+002534
+002535
+002536
+002537
+002538
+002539
+002540
+002541
+002542
+002543
+002544
+002545
+002546
+002547
+002548
+002549
+002550
+002551
+002552
+002553
+002554
+002555
+002556
+002557
+002558
+002559
+002560
+002561
+002562
+002563
+002564
+002565
+002566
+002567
+002568
+002569
+002570
+002571
+002572
+002573
+002574
+002575
+002576
+002577
+002578
+002579
+002580
+002581
+002582
+002583
+002584
+002585
+002586
+002587
+002588
+002589
+002590
+002591
+002592
+002593
+002594
+002595
+002596
+002597
+002598
+002599
+002600
+002601
+002602
+002603
+002604
+002605
+002606
+002607
+002608
+002609
+002610
+002611
+002612
+002613
+002614
+002615
+002616
+002617
+002618
+002619
+002620
+002621
+002622
+002623
+002624
+002625
+002626
+002627
+002628
+002629
+002630
+002631
+002632
+002633
+002634
+002635
+002636
+002637
+002638
+002639
+002640
+002641
+002642
+002643
+002644
+002645
+002646
+002647
+002648
+002649
+002650
+002651
+002652
+002653
+002654
+002655
+002656
+002657
+002658
+002659
+002660
+002661
+002662
+002663
+002664
+002665
+002666
+002667
+002668
+002669
+002670
+002671
+002672
+002673
+002674
+002675
+002676
+002677
+002678
+002679
+002680
+002681
+002682
+002683
+002684
+002685
+002686
+002687
+002688
+002689
+002690
+002691
+002692
+002693
+002694
+002695
+002696
+002697
+002698
+002699
+002700
+002701
+002702
+002703
+002704
+002705
+002706
+002707
+002708
+002709
+002710
+002711
+002712
+002713
+002714
+002715
+002716
+002717
+002718
+002719
+002720
+002721
+002722
+002723
+002724
+002725
+002726
+002727
+002728
+002729
+002730
+002731
+002732
+002733
+002734
+002735
+002736
+002737
+002738
+002739
+002740
+002741
+002742
+002743
+002744
+002745
+002746
+002747
+002748
+002749
+002750
+002751
+002752
+002753
+002754
+002755
+002756
+002757
+002758
+002759
+002760
+002761
+002762
+002763
+002764
+002765
+002766
+002767
+002768
+002769
+002770
+002771
+002772
+002773
+002774
+002775
+002776
+002777
+002778
+002779
+002780
+002781
+002782
+002783
+002784
+002785
+002786
+002787
+002788
+002789
+002790
+002791
+002792
+002793
+002794
+002795
+002796
+002797
+002798
+002799
+002800
+002801
+002802
+002803
+002804
+002805
+002806
+002807
+002808
+002809
+002810
+002811
+002812
+002813
+002814
+002815
+002816
+002817
+002818
+002819
+002820
+002821
+002822
+002823
+002824
+002825
+002826
+002827
+002828
+002829
+002830
+002831
+002832
+002833
+002834
+002835
+002836
+002837
+002838
+002839
+002840
+002841
+002842
+002843
+002844
+002845
+002846
+002847
+002848
+002849
+002850
+002851
+002852
+002853
+002854
+002855
+002856
+002857
+002858
+002859
+002860
+002861
+002862
+002863
+002864
+002865
+002866
+002867
+002868
+002869
+002870
+002871
+002872
+002873
+002874
+002875
+002876
+002877
+002878
+002879
+002880
+002881
+002882
+002883
+002884
+002885
+002886
+002887
+002888
+002889
+002890
+002891
+002892
+002893
+002894
+002895
+002896
+002897
+002898
+002899
+002900
+002901
+002902
+002903
+002904
+002905
+002906
+002907
+002908
+002909
+002910
+002911
+002912
+002913
+002914
+002915
+002916
+002917
+002918
+002919
+002920
+002921
+002922
+002923
+002924
+002925
+002926
+002927
+002928
+002929
+002930
+002931
+002932
+002933
+002934
+002935
+002936
+002937
+002938
+002939
+002940
+002941
+002942
+002943
+002944
+002945
+002946
+002947
+002948
+002949
+002950
+002951
+002952
+002953
+002954
+002955
+002956
+002957
+002958
+002959
+002960
+002961
+002962
+002963
+002964
+002965
+002966
+002967
+002968
+002969
+002970
+002971
+002972
+002973
+002974
+002975
+002976
+002977
+002978
+002979
+002980
+002981
+002982
+002983
+002984
+002985
+002986
+002987
+002988
+002989
+002990
+002991
+002992
+002993
+002994
+002995
+002996
+002997
+002998
+002999
+003000
+003001
+003002
+003003
+003004
+003005
+003006
+003007
+003008
+003009
+003010
+003011
+003012
+003013
+003014
+003015
+003016
+003017
+003018
+003019
+003020
+003021
+003022
+003023
+003024
+003025
+003026
+003027
+003028
+003029
+003030
+003031
+003032
+003033
+003034
+003035
+003036
+003037
+003038
+003039
+003040
+003041
+003042
+003043
+003044
+003045
+003046
+003047
+003048
+003049
+003050
+003051
+003052
+003053
+003054
+003055
+003056
+003057
+003058
+003059
+003060
+003061
+003062
+003063
+003064
+003065
+003066
+003067
+003068
+003069
+003070
+003071
+003072
+003073
+003074
+003075
+003076
+003077
+003078
+003079
+003080
+003081
+003082
+003083
+003084
+003085
+003086
+003087
+003088
+003089
+003090
+003091
+003092
+003093
+003094
+003095
+003096
+003097
+003098
+003099
+003100
+003101
+003102
+003103
+003104
+003105
+003106
+003107
+003108
+003109
+003110
+003111
+003112
+003113
+003114
+003115
+003116
+003117
+003118
+003119
+003120
+003121
+003122
+003123
+003124
+003125
+003126
+003127
+003128
+003129
+003130
+003131
+003132
+003133
+003134
+003135
+003136
+003137
+003138
+003139
+003140
+003141
+003142
+003143
+003144
+003145
+003146
+003147
+003148
+003149
+003150
+003151
+003152
+003153
+003154
+003155
+003156
+003157
+003158
+003159
+003160
+003161
+003162
+003163
+003164
+003165
+003166
+003167
+003168
+003169
+003170
+003171
+003172
+003173
+003174
+003175
+003176
+003177
+003178
+003179
+003180
+003181
+003182
+003183
+003184
+003185
+003186
+003187
+003188
+003189
+003190
+003191
+003192
+003193
+003194
+003195
+003196
+003197
+003198
+003199
+003200
+003201
+003202
+003203
+003204
+003205
+003206
+003207
+003208
+003209
+003210
+003211
+003212
+003213
+003214
+003215
+003216
+003217
+003218
+003219
+003220
+003221
+003222
+003223
+003224
+003225
+003226
+003227
+003228
+003229
+003230
+003231
+003232
+003233
+003234
+003235
+003236
+003237
+003238
+003239
+003240
+003241
+003242
+003243
+003244
+003245
+003246
+003247
+003248
+003249
+003250
+003251
+003252
+003253
+003254
+003255
+003256
+003257
+003258
+003259
+003260
+003261
+003262
+003263
+003264
+003265
+003266
+003267
+003268
+003269
+003270
+003271
+003272
+003273
+003274
+003275
+003276
+003277
+003278
+003279
+003280
+003281
+003282
+003283
+003284
+003285
+003286
+003287
+003288
+003289
+003290
+003291
+003292
+003293
+003294
+003295
+003296
+003297
+003298
+003299
+003300
+003301
+003302
+003303
+003304
+003305
+003306
+003307
+003308
+003309
+003310
+003311
+003312
+003313
+003314
+003315
+003316
+003317
+003318
+003319
+003320
+003321
+003322
+003323
+003324
+003325
+003326
+003327
+003328
+003329
+003330
+003331
+003332
+003333
+003334
+003335
+003336
+003337
+003338
+003339
+003340
+003341
+003342
+003343
+003344
+003345
+003346
+003347
+003348
+003349
+003350
+003351
+003352
+003353
+003354
+003355
+003356
+003357
+003358
+003359
+003360
+003361
+003362
+003363
+003364
+003365
+003366
+003367
+003368
+003369
+003370
+003371
+003372
+003373
+003374
+003375
+003376
+003377
+003378
+003379
+003380
+003381
+003382
+003383
+003384
+003385
+003386
+003387
+003388
+003389
+003390
+003391
+003392
+003393
+003394
+003395
+003396
+003397
+003398
+003399
+003400
+003401
+003402
+003403
+003404
+003405
+003406
+003407
+003408
+003409
+003410
+003411
+003412
+003413
+003414
+003415
+003416
+003417
+003418
+003419
+003420
+003421
+003422
+003423
+003424
+003425
+003426
+003427
+003428
+003429
+003430
+003431
+003432
+003433
+003434
+003435
+003436
+003437
+003438
+003439
+003440
+003441
+003442
+003443
+003444
+003445
+003446
+003447
+003448
+003449
+003450
+003451
+003452
+003453
+003454
+003455
+003456
+003457
+003458
+003459
+003460
+003461
+003462
+003463
+003464
+003465
+003466
+003467
+003468
+003469
+003470
+003471
+003472
+003473
+003474
+003475
+003476
+003477
+003478
+003479
+003480
+003481
+003482
+003483
+003484
+003485
+003486
+003487
+003488
+003489
+003490
+003491
+003492
+003493
+003494
+003495
+003496
+003497
+003498
+003499
+003500
+003501
+003502
+003503
+003504
+003505
+003506
+003507
+003508
+003509
+003510
+003511
+003512
+003513
+003514
+003515
+003516
+003517
+003518
+003519
+003520
+003521
+003522
+003523
+003524
+003525
+003526
+003527
+003528
+003529
+003530
+003531
+003532
+003533
+003534
+003535
+003536
+003537
+003538
+003539
+003540
+003541
+003542
+003543
+003544
+003545
+003546
+003547
+003548
+003549
+003550
+003551
+003552
+003553
+003554
+003555
+003556
+003557
+003558
+003559
+003560
+003561
+003562
+003563
+003564
+003565
+003566
+003567
+003568
+003569
+003570
+003571
+003572
+003573
+003574
+003575
+003576
+003577
+003578
+003579
+003580
+003581
+003582
+003583
+003584
+003585
+003586
+003587
+003588
+003589
+003590
+003591
+003592
+003593
+003594
+003595
+003596
+003597
+003598
+003599
+003600
+003601
+003602
+003603
+003604
+003605
+003606
+003607
+003608
+003609
+003610
+003611
+003612
+003613
+003614
+003615
+003616
+003617
+003618
+003619
+003620
+003621
+003622
+003623
+003624
+003625
+003626
+003627
+003628
+003629
+003630
+003631
+003632
+003633
+003634
+003635
+003636
+003637
+003638
+003639
+003640
+003641
+003642
+003643
+003644
+003645
+003646
+003647
+003648
+003649
+003650
+003651
+003652
+003653
+003654
+003655
+003656
+003657
+003658
+003659
+003660
+003661
+003662
+003663
+003664
+003665
+003666
+003667
+003668
+003669
+003670
+003671
+003672
+003673
+003674
+003675
+003676
+003677
+003678
+003679
+003680
+003681
+003682
+003683
+003684
+003685
+003686
+003687
+003688
+003689
+003690
+003691
+003692
+003693
+003694
+003695
+003696
+003697
+003698
+003699
+003700
+003701
+003702
+003703
+003704
+003705
+003706
+003707
+003708
+003709
+003710
+003711
+003712
+003713
+003714
+003715
+003716
+003717
+003718
+003719
+003720
+003721
+003722
+003723
+003724
+003725
+003726
+003727
+003728
+003729
+003730
+003731
+003732
+003733
+003734
+003735
+003736
+003737
+003738
+003739
+003740
+003741
+003742
+003743
+003744
+003745
+003746
+003747
+003748
+003749
+003750
+003751
+003752
+003753
+003754
+003755
+003756
+003757
+003758
+003759
+003760
+003761
+003762
+003763
+003764
+003765
+003766
+003767
+003768
+003769
+003770
+003771
+003772
+003773
+003774
+003775
+003776
+003777
+003778
+003779
+003780
+003781
+003782
+003783
+003784
+003785
+003786
+003787
+003788
+003789
+003790
+003791
+003792
+003793
+003794
+003795
+003796
+003797
+003798
+003799
+003800
+003801
+003802
+003803
+003804
+003805
+003806
+003807
+003808
+003809
+003810
+003811
+003812
+003813
+003814
+003815
+003816
+003817
+003818
+003819
+003820
+003821
+003822
+003823
+003824
+003825
+003826
+003827
+003828
+003829
+003830
+003831
+003832
+003833
+003834
+003835
+003836
+003837
+003838
+003839
+003840
+003841
+003842
+003843
+003844
+003845
+003846
+003847
+003848
+003849
+003850
+003851
+003852
+003853
+003854
+003855
+003856
+003857
+003858
+003859
+003860
+003861
+003862
+003863
+003864
+003865
+003866
+003867
+003868
+003869
+003870
+003871
+003872
+003873
+003874
+003875
+003876
+003877
+003878
+003879
+003880
+003881
+003882
+003883
+003884
+003885
+003886
+003887
+003888
+003889
+003890
+003891
+003892
+003893
+003894
+003895
+003896
+003897
+003898
+003899
+003900
+003901
+003902
+003903
+003904
+003905
+003906
+003907
+003908
+003909
+003910
+003911
+003912
+003913
+003914
+003915
+003916
+003917
+003918
+003919
+003920
+003921
+003922
+003923
+003924
+003925
+003926
+003927
+003928
+003929
+003930
+003931
+003932
+003933
+003934
+003935
+003936
+003937
+003938
+003939
+003940
+003941
+003942
+003943
+003944
+003945
+003946
+003947
+003948
+003949
+003950
+003951
+003952
+003953
+003954
+003955
+003956
+003957
+003958
+003959
+003960
+003961
+003962
+003963
+003964
+003965
+003966
+003967
+003968
+003969
+003970
+003971
+003972
+003973
+003974
+003975
+003976
+003977
+003978
+003979
+003980
+003981
+003982
+003983
+003984
+003985
+003986
+003987
+003988
+003989
+003990
+003991
+003992
+003993
+003994
+003995
+003996
+003997
+003998
+003999
+004000
+004001
+004002
+004003
+004004
+004005
+004006
+004007
+004008
+004009
+004010
+004011
+004012
+004013
+004014
+004015
+004016
+004017
+004018
+004019
+004020
+004021
+004022
+004023
+004024
+004025
+004026
+004027
+004028
+004029
+004030
+004031
+004032
+004033
+004034
+004035
+004036
+004037
+004038
+004039
+004040
+004041
+004042
+004043
+004044
+004045
+004046
+004047
+004048
+004049
+004050
+004051
+004052
+004053
+004054
+004055
+004056
+004057
+004058
+004059
+004060
+004061
+004062
+004063
+004064
+004065
+004066
+004067
+004068
+004069
+004070
+004071
+004072
+004073
+004074
+004075
+004076
+004077
+004078
+004079
+004080
+004081
+004082
+004083
+004084
+004085
+004086
+004087
+004088
+004089
+004090
+004091
+004092
+004093
+004094
+004095
+004096
+004097
+004098
+004099
+004100
+004101
+004102
+004103
+004104
+004105
+004106
+004107
+004108
+004109
+004110
+004111
+004112
+004113
+004114
+004115
+004116
+004117
+004118
+004119
+004120
+004121
+004122
+004123
+004124
+004125
+004126
+004127
+004128
+004129
+004130
+004131
+004132
+004133
+004134
+004135
+004136
+004137
+004138
+004139
+004140
+004141
+004142
+004143
+004144
+004145
+004146
+004147
+004148
+004149
+004150
+004151
+004152
+004153
+004154
+004155
+004156
+004157
+004158
+004159
+004160
+004161
+004162
+004163
+004164
+004165
+004166
+004167
+004168
+004169
+004170
+004171
+004172
+004173
+004174
+004175
+004176
+004177
+004178
+004179
+004180
+004181
+004182
+004183
+004184
+004185
+004186
+004187
+004188
+004189
+004190
+004191
+004192
+004193
+004194
+004195
+004196
+004197
+004198
+004199
+004200
+004201
+004202
+004203
+004204
+004205
+004206
+004207
+004208
+004209
+004210
+004211
+004212
+004213
+004214
+004215
+004216
+004217
+004218
+004219
+004220
+004221
+004222
+004223
+004224
+004225
+004226
+004227
+004228
+004229
+004230
+004231
+004232
+004233
+004234
+004235
+004236
+004237
+004238
+004239
+004240
+004241
+004242
+004243
+004244
+004245
+004246
+004247
+004248
+004249
+004250
+004251
+004252
+004253
+004254
+004255
+004256
+004257
+004258
+004259
+004260
+004261
+004262
+004263
+004264
+004265
+004266
+004267
+004268
+004269
+004270
+004271
+004272
+004273
+004274
+004275
+004276
+004277
+004278
+004279
+004280
+004281
+004282
+004283
+004284
+004285
+004286
+004287
+004288
+004289
+004290
+004291
+004292
+004293
+004294
+004295
+004296
+004297
+004298
+004299
+004300
+004301
+004302
+004303
+004304
+004305
+004306
+004307
+004308
+004309
+004310
+004311
+004312
+004313
+004314
+004315
+004316
+004317
+004318
+004319
+004320
+004321
+004322
+004323
+004324
+004325
+004326
+004327
+004328
+004329
+004330
+004331
+004332
+004333
+004334
+004335
+004336
+004337
+004338
+004339
+004340
+004341
+004342
+004343
+004344
+004345
+004346
+004347
+004348
+004349
+004350
+004351
+004352
+004353
+004354
+004355
+004356
+004357
+004358
+004359
+004360
+004361
+004362
+004363
+004364
+004365
+004366
+004367
+004368
+004369
+004370
+004371
+004372
+004373
+004374
+004375
+004376
+004377
+004378
+004379
+004380
+004381
+004382
+004383
+004384
+004385
+004386
+004387
+004388
+004389
+004390
+004391
+004392
+004393
+004394
+004395
+004396
+004397
+004398
+004399
+004400
+004401
+004402
+004403
+004404
+004405
+004406
+004407
+004408
+004409
+004410
+004411
+004412
+004413
+004414
+004415
+004416
+004417
+004418
+004419
+004420
+004421
+004422
+004423
+004424
+004425
+004426
+004427
+004428
+004429
+004430
+004431
+004432
+004433
+004434
+004435
+004436
+004437
+004438
+004439
+004440
+004441
+004442
+004443
+004444
+004445
+004446
+004447
+004448
+004449
+004450
+004451
+004452
+004453
+004454
+004455
+004456
+004457
+004458
+004459
+004460
+004461
+004462
+004463
+004464
+004465
+004466
+004467
+004468
+004469
+004470
+004471
+004472
+004473
+004474
+004475
+004476
+004477
+004478
+004479
+004480
+004481
+004482
+004483
+004484
+004485
+004486
+004487
+004488
+004489
+004490
+004491
+004492
+004493
+004494
+004495
+004496
+004497
+004498
+004499
+004500
+004501
+004502
+004503
+004504
+004505
+004506
+004507
+004508
+004509
+004510
+004511
+004512
+004513
+004514
+004515
+004516
+004517
+004518
+004519
+004520
+004521
+004522
+004523
+004524
+004525
+004526
+004527
+004528
+004529
+004530
+004531
+004532
+004533
+004534
+004535
+004536
+004537
+004538
+004539
+004540
+004541
+004542
+004543
+004544
+004545
+004546
+004547
+004548
+004549
+004550
+004551
+004552
+004553
+004554
+004555
+004556
+004557
+004558
+004559
+004560
+004561
+004562
+004563
+004564
+004565
+004566
+004567
+004568
+004569
+004570
+004571
+004572
+004573
+004574
+004575
+004576
+004577
+004578
+004579
+004580
+004581
+004582
+004583
+004584
+004585
+004586
+004587
+004588
+004589
+004590
+004591
+004592
+004593
+004594
+004595
+004596
+004597
+004598
+004599
+004600
+004601
+004602
+004603
+004604
+004605
+004606
+004607
+004608
+004609
+004610
+004611
+004612
+004613
+004614
+004615
+004616
+004617
+004618
+004619
+004620
+004621
+004622
+004623
+004624
+004625
+004626
+004627
+004628
+004629
+004630
+004631
+004632
+004633
+004634
+004635
+004636
+004637
+004638
+004639
+004640
+004641
+004642
+004643
+004644
+004645
+004646
+004647
+004648
+004649
+004650
+004651
+004652
+004653
+004654
+004655
+004656
+004657
+004658
+004659
+004660
+004661
+004662
+004663
+004664
+004665
+004666
+004667
+004668
+004669
+004670
+004671
+004672
+004673
+004674
+004675
+004676
+004677
+004678
+004679
+004680
+004681
+004682
+004683
+004684
+004685
+004686
+004687
+004688
+004689
+004690
+004691
+004692
+004693
+004694
+004695
+004696
+004697
+004698
+004699
+004700
+004701
+004702
+004703
+004704
+004705
+004706
+004707
+004708
+004709
+004710
+004711
+004712
+004713
+004714
+004715
+004716
+004717
+004718
+004719
+004720
+004721
+004722
+004723
+004724
+004725
+004726
+004727
+004728
+004729
+004730
+004731
+004732
+004733
+004734
+004735
+004736
+004737
+004738
+004739
+004740
+004741
+004742
+004743
+004744
+004745
+004746
+004747
+004748
+004749
+004750
+004751
+004752
+004753
+004754
+004755
+004756
+004757
+004758
+004759
+004760
+004761
+004762
+004763
+004764
+004765
+004766
+004767
+004768
+004769
+004770
+004771
+004772
+004773
+004774
+004775
+004776
+004777
+004778
+004779
+004780
+004781
+004782
+004783
+004784
+004785
+004786
+004787
+004788
+004789
+004790
+004791
+004792
+004793
+004794
+004795
+004796
+004797
+004798
+004799
+004800
+004801
+004802
+004803
+004804
+004805
+004806
+004807
+004808
+004809
+004810
+004811
+004812
+004813
+004814
+004815
+004816
+004817
+004818
+004819
+004820
+004821
+004822
+004823
+004824
+004825
+004826
+004827
+004828
+004829
+004830
+004831
+004832
+004833
+004834
+004835
+004836
+004837
+004838
+004839
+004840
+004841
+004842
+004843
+004844
+004845
+004846
+004847
+004848
+004849
+004850
+004851
+004852
+004853
+004854
+004855
+004856
+004857
+004858
+004859
+004860
+004861
+004862
+004863
+004864
+004865
+004866
+004867
+004868
+004869
+004870
+004871
+004872
+004873
+004874
+004875
+004876
+004877
+004878
+004879
+004880
+004881
+004882
+004883
+004884
+004885
+004886
+004887
+004888
+004889
+004890
+004891
+004892
+004893
+004894
+004895
+004896
+004897
+004898
+004899
+004900
+004901
+004902
+004903
+004904
+004905
+004906
+004907
+004908
+004909
+004910
+004911
+004912
+004913
+004914
+004915
+004916
+004917
+004918
+004919
+004920
+004921
+004922
+004923
+004924
+004925
+004926
+004927
+004928
+004929
+004930
+004931
+004932
+004933
+004934
+004935
+004936
+004937
+004938
+004939
+004940
+004941
+004942
+004943
+004944
+004945
+004946
+004947
+004948
+004949
+004950
+004951
+004952
+004953
+004954
+004955
+004956
+004957
+004958
+004959
+004960
+004961
+004962
+004963
+004964
+004965
+004966
+004967
+004968
+004969
+004970
+004971
+004972
+004973
+004974
+004975
+004976
+004977
+004978
+004979
+004980
+004981
+004982
+004983
+004984
+004985
+004986
+004987
+004988
+004989
+004990
+004991
+004992
+004993
+004994
+004995
+004996
+004997
+004998
+004999
+005000
+005001
+005002
+005003
+005004
+005005
+005006
+005007
+005008
+005009
+005010
+005011
+005012
+005013
+005014
+005015
+005016
+005017
+005018
+005019
+005020
+005021
+005022
+005023
+005024
+005025
+005026
+005027
+005028
+005029
+005030
+005031
+005032
+005033
+005034
+005035
+005036
+005037
+005038
+005039
+005040
+005041
+005042
+005043
+005044
+005045
+005046
+005047
+005048
+005049
+005050
+005051
+005052
+005053
+005054
+005055
+005056
+005057
+005058
+005059
+005060
+005061
+005062
+005063
+005064
+005065
+005066
+005067
+005068
+005069
+005070
+005071
+005072
+005073
+005074
+005075
+005076
+005077
+005078
+005079
+005080
+005081
+005082
+005083
+005084
+005085
+005086
+005087
+005088
+005089
+005090
+005091
+005092
+005093
+005094
+005095
+005096
+005097
+005098
+005099
+005100
+005101
+005102
+005103
+005104
+005105
+005106
+005107
+005108
+005109
+005110
+005111
+005112
+005113
+005114
+005115
+005116
+005117
+005118
+005119
+005120
+005121
+005122
+005123
+005124
+005125
+005126
+005127
+005128
+005129
+005130
+005131
+005132
+005133
+005134
+005135
+005136
+005137
+005138
+005139
+005140
+005141
+005142
+005143
+005144
+005145
+005146
+005147
+005148
+005149
+005150
+005151
+005152
+005153
+005154
+005155
+005156
+005157
+005158
+005159
+005160
+005161
+005162
+005163
+005164
+005165
+005166
+005167
+005168
+005169
+005170
+005171
+005172
+005173
+005174
+005175
+005176
+005177
+005178
+005179
+005180
+005181
+005182
+005183
+005184
+005185
+005186
+005187
+005188
+005189
+005190
+005191
+005192
+005193
+005194
+005195
+005196
+005197
+005198
+005199
+005200
+005201
+005202
+005203
+005204
+005205
+005206
+005207
+005208
+005209
+005210
+005211
+005212
+005213
+005214
+005215
+005216
+005217
+005218
+005219
+005220
+005221
+005222
+005223
+005224
+005225
+005226
+005227
+005228
+005229
+005230
+005231
+005232
+005233
+005234
+005235
+005236
+005237
+005238
+005239
+005240
+005241
+005242
+005243
+005244
+005245
+005246
+005247
+005248
+005249
+005250
+005251
+005252
+005253
+005254
+005255
+005256
+005257
+005258
+005259
+005260
+005261
+005262
+005263
+005264
+005265
+005266
+005267
+005268
+005269
+005270
+005271
+005272
+005273
+005274
+005275
+005276
+005277
+005278
+005279
+005280
+005281
+005282
+005283
+005284
+005285
+005286
+005287
+005288
+005289
+005290
+005291
+005292
+005293
+005294
+005295
+005296
+005297
+005298
+005299
+005300
+005301
+005302
+005303
+005304
+005305
+005306
+005307
+005308
+005309
+005310
+005311
+005312
+005313
+005314
+005315
+005316
+005317
+005318
+005319
+005320
+005321
+005322
+005323
+005324
+005325
+005326
+005327
+005328
+005329
+005330
+005331
+005332
+005333
+005334
+005335
+005336
+005337
+005338
+005339
+005340
+005341
+005342
+005343
+005344
+005345
+005346
+005347
+005348
+005349
+005350
+005351
+005352
+005353
+005354
+005355
+005356
+005357
+005358
+005359
+005360
+005361
+005362
+005363
+005364
+005365
+005366
+005367
+005368
+005369
+005370
+005371
+005372
+005373
+005374
+005375
+005376
+005377
+005378
+005379
+005380
+005381
+005382
+005383
+005384
+005385
+005386
+005387
+005388
+005389
+005390
+005391
+005392
+005393
+005394
+005395
+005396
+005397
+005398
+005399
+005400
+005401
+005402
+005403
+005404
+005405
+005406
+005407
+005408
+005409
+005410
+005411
+005412
+005413
+005414
+005415
+005416
+005417
+005418
+005419
+005420
+005421
+005422
+005423
+005424
+005425
+005426
+005427
+005428
+005429
+005430
+005431
+005432
+005433
+005434
+005435
+005436
+005437
+005438
+005439
+005440
+005441
+005442
+005443
+005444
+005445
+005446
+005447
+005448
+005449
+005450
+005451
+005452
+005453
+005454
+005455
+005456
+005457
+005458
+005459
+005460
+005461
+005462
+005463
+005464
+005465
+005466
+005467
+005468
+005469
+005470
+005471
+005472
+005473
+005474
+005475
+005476
+005477
+005478
+005479
+005480
+005481
+005482
+005483
+005484
+005485
+005486
+005487
+005488
+005489
+005490
+005491
+005492
+005493
+005494
+005495
+005496
+005497
+005498
+005499
+005500
+005501
+005502
+005503
+005504
+005505
+005506
+005507
+005508
+005509
+005510
+005511
+005512
+005513
+005514
+005515
+005516
+005517
+005518
+005519
+005520
+005521
+005522
+005523
+005524
+005525
+005526
+005527
+005528
+005529
+005530
+005531
+005532
+005533
+005534
+005535
+005536
+005537
+005538
+005539
+005540
+005541
+005542
+005543
+005544
+005545
+005546
+005547
+005548
+005549
+005550
+005551
+005552
+005553
+005554
+005555
+005556
+005557
+005558
+005559
+005560
+005561
+005562
+005563
+005564
+005565
+005566
+005567
+005568
+005569
+005570
+005571
+005572
+005573
+005574
+005575
+005576
+005577
+005578
+005579
+005580
+005581
+005582
+005583
+005584
+005585
+005586
+005587
+005588
+005589
+005590
+005591
+005592
+005593
+005594
+005595
+005596
+005597
+005598
+005599
+005600
+005601
+005602
+005603
+005604
+005605
+005606
+005607
+005608
+005609
+005610
+005611
+005612
+005613
+005614
+005615
+005616
+005617
+005618
+005619
+005620
+005621
+005622
+005623
+005624
+005625
+005626
+005627
+005628
+005629
+005630
+005631
+005632
+005633
+005634
+005635
+005636
+005637
+005638
+005639
+005640
+005641
+005642
+005643
+005644
+005645
+005646
+005647
+005648
+005649
+005650
+005651
+005652
+005653
+005654
+005655
+005656
+005657
+005658
+005659
+005660
+005661
+005662
+005663
+005664
+005665
+005666
+005667
+005668
+005669
+005670
+005671
+005672
+005673
+005674
+005675
+005676
+005677
+005678
+005679
+005680
+005681
+005682
+005683
+005684
+005685
+005686
+005687
+005688
+005689
+005690
+005691
+005692
+005693
+005694
+005695
+005696
+005697
+005698
+005699
+005700
+005701
+005702
+005703
+005704
+005705
+005706
+005707
+005708
+005709
+005710
+005711
+005712
+005713
+005714
+005715
+005716
+005717
+005718
+005719
+005720
+005721
+005722
+005723
+005724
+005725
+005726
+005727
+005728
+005729
+005730
+005731
+005732
+005733
+005734
+005735
+005736
+005737
+005738
+005739
+005740
+005741
+005742
+005743
+005744
+005745
+005746
+005747
+005748
+005749
+005750
+005751
+005752
+005753
+005754
+005755
+005756
+005757
+005758
+005759
+005760
+005761
+005762
+005763
+005764
+005765
+005766
+005767
+005768
+005769
+005770
+005771
+005772
+005773
+005774
+005775
+005776
+005777
+005778
+005779
+005780
+005781
+005782
+005783
+005784
+005785
+005786
+005787
+005788
+005789
+005790
+005791
+005792
+005793
+005794
+005795
+005796
+005797
+005798
+005799
+005800
+005801
+005802
+005803
+005804
+005805
+005806
+005807
+005808
+005809
+005810
+005811
+005812
+005813
+005814
+005815
+005816
+005817
+005818
+005819
+005820
+005821
+005822
+005823
+005824
+005825
+005826
+005827
+005828
+005829
+005830
+005831
+005832
+005833
+005834
+005835
+005836
+005837
+005838
+005839
+005840
+005841
+005842
+005843
+005844
+005845
+005846
+005847
+005848
+005849
+005850
+005851
+005852
+005853
+005854
+005855
+005856
+005857
+005858
+005859
+005860
+005861
+005862
+005863
+005864
+005865
+005866
+005867
+005868
+005869
+005870
+005871
+005872
+005873
+005874
+005875
+005876
+005877
+005878
+005879
+005880
+005881
+005882
+005883
+005884
+005885
+005886
+005887
+005888
+005889
+005890
+005891
+005892
+005893
+005894
+005895
+005896
+005897
+005898
+005899
+005900
+005901
+005902
+005903
+005904
+005905
+005906
+005907
+005908
+005909
+005910
+005911
+005912
+005913
+005914
+005915
+005916
+005917
+005918
+005919
+005920
+005921
+005922
+005923
+005924
+005925
+005926
+005927
+005928
+005929
+005930
+005931
+005932
+005933
+005934
+005935
+005936
+005937
+005938
+005939
+005940
+005941
+005942
+005943
+005944
+005945
+005946
+005947
+005948
+005949
+005950
+005951
+005952
+005953
+005954
+005955
+005956
+005957
+005958
+005959
+005960
+005961
+005962
+005963
+005964
+005965
+005966
+005967
+005968
+005969
+005970
+005971
+005972
+005973
+005974
+005975
+005976
+005977
+005978
+005979
+005980
+005981
+005982
+005983
+005984
+005985
+005986
+005987
+005988
+005989
+005990
+005991
+005992
+005993
+005994
+005995
+005996
+005997
+005998
+005999
+006000
+006001
+006002
+006003
+006004
+006005
+006006
+006007
+006008
+006009
+006010
+006011
+006012
+006013
+006014
+006015
+006016
+006017
+006018
+006019
+006020
+006021
+006022
+006023
+006024
+006025
+006026
+006027
+006028
+006029
+006030
+006031
+006032
+006033
+006034
+006035
+006036
+006037
+006038
+006039
+006040
+006041
+006042
+006043
+006044
+006045
+006046
+006047
+006048
+006049
+006050
+006051
+006052
+006053
+006054
+006055
+006056
+006057
+006058
+006059
+006060
+006061
+006062
+006063
+006064
+006065
+006066
+006067
+006068
+006069
+006070
+006071
+006072
+006073
+006074
+006075
+006076
+006077
+006078
+006079
+006080
+006081
+006082
+006083
+006084
+006085
+006086
+006087
+006088
+006089
+006090
+006091
+006092
+006093
+006094
+006095
+006096
+006097
+006098
+006099
+006100
+006101
+006102
+006103
+006104
+006105
+006106
+006107
+006108
+006109
+006110
+006111
+006112
+006113
+006114
+006115
+006116
+006117
+006118
+006119
+006120
+006121
+006122
+006123
+006124
+006125
+006126
+006127
+006128
+006129
+006130
+006131
+006132
+006133
+006134
+006135
+006136
+006137
+006138
+006139
+006140
+006141
+006142
+006143
+006144
+006145
+006146
+006147
+006148
+006149
+006150
+006151
+006152
+006153
+006154
+006155
+006156
+006157
+006158
+006159
+006160
+006161
+006162
+006163
+006164
+006165
+006166
+006167
+006168
+006169
+006170
+006171
+006172
+006173
+006174
+006175
+006176
+006177
+006178
+006179
+006180
+006181
+006182
+006183
+006184
+006185
+006186
+006187
+006188
+006189
+006190
+006191
+006192
+006193
+006194
+006195
+006196
+006197
+006198
+006199
+006200
+006201
+006202
+006203
+006204
+006205
+006206
+006207
+006208
+006209
+006210
+006211
+006212
+006213
+006214
+006215
+006216
+006217
+006218
+006219
+006220
+006221
+006222
+006223
+006224
+006225
+006226
+006227
+006228
+006229
+006230
+006231
+006232
+006233
+006234
+006235
+006236
+006237
+006238
+006239
+006240
+006241
+006242
+006243
+006244
+006245
+006246
+006247
+006248
+006249
+006250
+006251
+006252
+006253
+006254
+006255
+006256
+006257
+006258
+006259
+006260
+006261
+006262
+006263
+006264
+006265
+006266
+006267
+006268
+006269
+006270
+006271
+006272
+006273
+006274
+006275
+006276
+006277
+006278
+006279
+006280
+006281
+006282
+006283
+006284
+006285
+006286
+006287
+006288
+006289
+006290
+006291
+006292
+006293
+006294
+006295
+006296
+006297
+006298
+006299
+006300
+006301
+006302
+006303
+006304
+006305
+006306
+006307
+006308
+006309
+006310
+006311
+006312
+006313
+006314
+006315
+006316
+006317
+006318
+006319
+006320
+006321
+006322
+006323
+006324
+006325
+006326
+006327
+006328
+006329
+006330
+006331
+006332
+006333
+006334
+006335
+006336
+006337
+006338
+006339
+006340
+006341
+006342
+006343
+006344
+006345
+006346
+006347
+006348
+006349
+006350
+006351
+006352
+006353
+006354
+006355
+006356
+006357
+006358
+006359
+006360
+006361
+006362
+006363
+006364
+006365
+006366
+006367
+006368
+006369
+006370
+006371
+006372
+006373
+006374
+006375
+006376
+006377
+006378
+006379
+006380
+006381
+006382
+006383
+006384
+006385
+006386
+006387
+006388
+006389
+006390
+006391
+006392
+006393
+006394
+006395
+006396
+006397
+006398
+006399
+006400
+006401
+006402
+006403
+006404
+006405
+006406
+006407
+006408
+006409
+006410
+006411
+006412
+006413
+006414
+006415
+006416
+006417
+006418
+006419
+006420
+006421
+006422
+006423
+006424
+006425
+006426
+006427
+006428
+006429
+006430
+006431
+006432
+006433
+006434
+006435
+006436
+006437
+006438
+006439
+006440
+006441
+006442
+006443
+006444
+006445
+006446
+006447
+006448
+006449
+006450
+006451
+006452
+006453
+006454
+006455
+006456
+006457
+006458
+006459
+006460
+006461
+006462
+006463
+006464
+006465
+006466
+006467
+006468
+006469
+006470
+006471
+006472
+006473
+006474
+006475
+006476
+006477
+006478
+006479
+006480
+006481
+006482
+006483
+006484
+006485
+006486
+006487
+006488
+006489
+006490
+006491
+006492
+006493
+006494
+006495
+006496
+006497
+006498
+006499
+006500
+006501
+006502
+006503
+006504
+006505
+006506
+006507
+006508
+006509
+006510
+006511
+006512
+006513
+006514
+006515
+006516
+006517
+006518
+006519
+006520
+006521
+006522
+006523
+006524
+006525
+006526
+006527
+006528
+006529
+006530
+006531
+006532
+006533
+006534
+006535
+006536
+006537
+006538
+006539
+006540
+006541
+006542
+006543
+006544
+006545
+006546
+006547
+006548
+006549
+006550
+006551
+006552
+006553
+006554
+006555
+006556
+006557
+006558
+006559
+006560
+006561
+006562
+006563
+006564
+006565
+006566
+006567
+006568
+006569
+006570
+006571
+006572
+006573
+006574
+006575
+006576
+006577
+006578
+006579
+006580
+006581
+006582
+006583
+006584
+006585
+006586
+006587
+006588
+006589
+006590
+006591
+006592
+006593
+006594
+006595
+006596
+006597
+006598
+006599
+006600
+006601
+006602
+006603
+006604
+006605
+006606
+006607
+006608
+006609
+006610
+006611
+006612
+006613
+006614
+006615
+006616
+006617
+006618
+006619
+006620
+006621
+006622
+006623
+006624
+006625
+006626
+006627
+006628
+006629
+006630
+006631
+006632
+006633
+006634
+006635
+006636
+006637
+006638
+006639
+006640
+006641
+006642
+006643
+006644
+006645
+006646
+006647
+006648
+006649
+006650
+006651
+006652
+006653
+006654
+006655
+006656
+006657
+006658
+006659
+006660
+006661
+006662
+006663
+006664
+006665
+006666
+006667
+006668
+006669
+006670
+006671
+006672
+006673
+006674
+006675
+006676
+006677
+006678
+006679
+006680
+006681
+006682
+006683
+006684
+006685
+006686
+006687
+006688
+006689
+006690
+006691
+006692
+006693
+006694
+006695
+006696
+006697
+006698
+006699
+006700
+006701
+006702
+006703
+006704
+006705
+006706
+006707
+006708
+006709
+006710
+006711
+006712
+006713
+006714
+006715
+006716
+006717
+006718
+006719
+006720
+006721
+006722
+006723
+006724
+006725
+006726
+006727
+006728
+006729
+006730
+006731
+006732
+006733
+006734
+006735
+006736
+006737
+006738
+006739
+006740
+006741
+006742
+006743
+006744
+006745
+006746
+006747
+006748
+006749
+006750
+006751
+006752
+006753
+006754
+006755
+006756
+006757
+006758
+006759
+006760
+006761
+006762
+006763
+006764
+006765
+006766
+006767
+006768
+006769
+006770
+006771
+006772
+006773
+006774
+006775
+006776
+006777
+006778
+006779
+006780
+006781
+006782
+006783
+006784
+006785
+006786
+006787
+006788
+006789
+006790
+006791
+006792
+006793
+006794
+006795
+006796
+006797
+006798
+006799
+006800
+006801
+006802
+006803
+006804
+006805
+006806
+006807
+006808
+006809
+006810
+006811
+006812
+006813
+006814
+006815
+006816
+006817
+006818
+006819
+006820
+006821
+006822
+006823
+006824
+006825
+006826
+006827
+006828
+006829
+006830
+006831
+006832
+006833
+006834
+006835
+006836
+006837
+006838
+006839
+006840
+006841
+006842
+006843
+006844
+006845
+006846
+006847
+006848
+006849
+006850
+006851
+006852
+006853
+006854
+006855
+006856
+006857
+006858
+006859
+006860
+006861
+006862
+006863
+006864
+006865
+006866
+006867
+006868
+006869
+006870
+006871
+006872
+006873
+006874
+006875
+006876
+006877
+006878
+006879
+006880
+006881
+006882
+006883
+006884
+006885
+006886
+006887
+006888
+006889
+006890
+006891
+006892
+006893
+006894
+006895
+006896
+006897
+006898
+006899
+006900
+006901
+006902
+006903
+006904
+006905
+006906
+006907
+006908
+006909
+006910
+006911
+006912
+006913
+006914
+006915
+006916
+006917
+006918
+006919
+006920
+006921
+006922
+006923
+006924
+006925
+006926
+006927
+006928
+006929
+006930
+006931
+006932
+006933
+006934
+006935
+006936
+006937
+006938
+006939
+006940
+006941
+006942
+006943
+006944
+006945
+006946
+006947
+006948
+006949
+006950
+006951
+006952
+006953
+006954
+006955
+006956
+006957
+006958
+006959
+006960
+006961
+006962
+006963
+006964
+006965
+006966
+006967
+006968
+006969
+006970
+006971
+006972
+006973
+006974
+006975
+006976
+006977
+006978
+006979
+006980
+006981
+006982
+006983
+006984
+006985
+006986
+006987
+006988
+006989
+006990
+006991
+006992
+006993
+006994
+006995
+006996
+006997
+006998
+006999
+007000
+007001
+007002
+007003
+007004
+007005
+007006
+007007
+007008
+007009
+007010
+007011
+007012
+007013
+007014
+007015
+007016
+007017
+007018
+007019
+007020
+007021
+007022
+007023
+007024
+007025
+007026
+007027
+007028
+007029
+007030
+007031
+007032
+007033
+007034
+007035
+007036
+007037
+007038
+007039
+007040
+007041
+007042
+007043
+007044
+007045
+007046
+007047
+007048
+007049
+007050
+007051
+007052
+007053
+007054
+007055
+007056
+007057
+007058
+007059
+007060
+007061
+007062
+007063
+007064
+007065
+007066
+007067
+007068
+007069
+007070
+007071
+007072
+007073
+007074
+007075
+007076
+007077
+007078
+007079
+007080
+007081
+007082
+007083
+007084
+007085
+007086
+007087
+007088
+007089
+007090
+007091
+007092
+007093
+007094
+007095
+007096
+007097
+007098
+007099
+007100
+007101
+007102
+007103
+007104
+007105
+007106
+007107
+007108
+007109
+007110
+007111
+007112
+007113
+007114
+007115
+007116
+007117
+007118
+007119
+007120
+007121
+007122
+007123
+007124
+007125
+007126
+007127
+007128
+007129
+007130
+007131
+007132
+007133
+007134
+007135
+007136
+007137
+007138
+007139
+007140
+007141
+007142
+007143
+007144
+007145
+007146
+007147
+007148
+007149
+007150
+007151
+007152
+007153
+007154
+007155
+007156
+007157
+007158
+007159
+007160
+007161
+007162
+007163
+007164
+007165
+007166
+007167
+007168
+007169
+007170
+007171
+007172
+007173
+007174
+007175
+007176
+007177
+007178
+007179
+007180
+007181
+007182
+007183
+007184
+007185
+007186
+007187
+007188
+007189
+007190
+007191
+007192
+007193
+007194
+007195
+007196
+007197
+007198
+007199
+007200
+007201
+007202
+007203
+007204
+007205
+007206
+007207
+007208
+007209
+007210
+007211
+007212
+007213
+007214
+007215
+007216
+007217
+007218
+007219
+007220
+007221
+007222
+007223
+007224
+007225
+007226
+007227
+007228
+007229
+007230
+007231
+007232
+007233
+007234
+007235
+007236
+007237
+007238
+007239
+007240
+007241
+007242
+007243
+007244
+007245
+007246
+007247
+007248
+007249
+007250
+007251
+007252
+007253
+007254
+007255
+007256
+007257
+007258
+007259
+007260
+007261
+007262
+007263
+007264
+007265
+007266
+007267
+007268
+007269
+007270
+007271
+007272
+007273
+007274
+007275
+007276
+007277
+007278
+007279
+007280
+007281
+007282
+007283
+007284
+007285
+007286
+007287
+007288
+007289
+007290
+007291
+007292
+007293
+007294
+007295
+007296
+007297
+007298
+007299
+007300
+007301
+007302
+007303
+007304
+007305
+007306
+007307
+007308
+007309
+007310
+007311
+007312
+007313
+007314
+007315
+007316
+007317
+007318
+007319
+007320
+007321
+007322
+007323
+007324
+007325
+007326
+007327
+007328
+007329
+007330
+007331
+007332
+007333
+007334
+007335
+007336
+007337
+007338
+007339
+007340
+007341
+007342
+007343
+007344
+007345
+007346
+007347
+007348
+007349
+007350
+007351
+007352
+007353
+007354
+007355
+007356
+007357
+007358
+007359
+007360
+007361
+007362
+007363
+007364
+007365
+007366
+007367
+007368
+007369
+007370
+007371
+007372
+007373
+007374
+007375
+007376
+007377
+007378
+007379
+007380
+007381
+007382
+007383
+007384
+007385
+007386
+007387
+007388
+007389
+007390
+007391
+007392
+007393
+007394
+007395
+007396
+007397
+007398
+007399
+007400
+007401
+007402
+007403
+007404
+007405
+007406
+007407
+007408
+007409
+007410
+007411
+007412
+007413
+007414
+007415
+007416
+007417
+007418
+007419
+007420
+007421
+007422
+007423
+007424
+007425
+007426
+007427
+007428
+007429
+007430
+007431
+007432
+007433
+007434
+007435
+007436
+007437
+007438
+007439
+007440
+007441
+007442
+007443
+007444
+007445
+007446
+007447
+007448
+007449
+007450
+007451
+007452
+007453
+007454
+007455
+007456
+007457
+007458
+007459
+007460
+007461
+007462
+007463
+007464
+007465
+007466
+007467
+007468
+007469
+007470
+007471
+007472
+007473
+007474
+007475
+007476
+007477
+007478
+007479
+007480
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/val.txt b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/val.txt
new file mode 100644
index 00000000000..258ca114774
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/ImageSets/val.txt
@@ -0,0 +1,3769 @@
+000001
+000002
+000004
+000005
+000006
+000008
+000015
+000019
+000020
+000021
+000023
+000024
+000025
+000027
+000028
+000031
+000033
+000035
+000037
+000039
+000040
+000042
+000047
+000048
+000050
+000052
+000053
+000058
+000059
+000061
+000062
+000063
+000065
+000066
+000076
+000077
+000078
+000081
+000089
+000090
+000093
+000094
+000098
+000102
+000104
+000106
+000107
+000108
+000116
+000117
+000118
+000122
+000124
+000126
+000128
+000132
+000134
+000135
+000137
+000139
+000140
+000143
+000147
+000151
+000152
+000153
+000156
+000159
+000161
+000167
+000168
+000169
+000170
+000173
+000174
+000175
+000181
+000182
+000183
+000186
+000187
+000188
+000190
+000191
+000192
+000194
+000195
+000196
+000197
+000199
+000201
+000203
+000204
+000207
+000211
+000212
+000213
+000216
+000218
+000223
+000224
+000226
+000229
+000230
+000231
+000234
+000235
+000236
+000237
+000239
+000242
+000246
+000247
+000248
+000249
+000250
+000251
+000252
+000260
+000262
+000263
+000265
+000266
+000268
+000269
+000270
+000272
+000273
+000278
+000279
+000281
+000283
+000284
+000289
+000290
+000291
+000293
+000297
+000301
+000302
+000305
+000307
+000308
+000309
+000311
+000312
+000314
+000315
+000319
+000320
+000321
+000323
+000324
+000327
+000328
+000329
+000332
+000333
+000335
+000336
+000340
+000341
+000343
+000345
+000346
+000347
+000350
+000351
+000352
+000354
+000355
+000356
+000357
+000359
+000360
+000361
+000362
+000365
+000366
+000369
+000370
+000372
+000373
+000376
+000377
+000378
+000379
+000381
+000382
+000383
+000385
+000386
+000388
+000391
+000392
+000393
+000394
+000395
+000396
+000397
+000398
+000399
+000401
+000402
+000403
+000404
+000407
+000408
+000409
+000413
+000414
+000415
+000419
+000420
+000422
+000427
+000428
+000429
+000430
+000436
+000437
+000440
+000443
+000446
+000448
+000450
+000451
+000452
+000453
+000454
+000455
+000457
+000459
+000463
+000468
+000469
+000472
+000473
+000475
+000476
+000477
+000478
+000479
+000480
+000481
+000485
+000486
+000489
+000491
+000492
+000493
+000494
+000495
+000496
+000498
+000499
+000503
+000504
+000506
+000508
+000509
+000510
+000512
+000515
+000517
+000519
+000521
+000524
+000527
+000528
+000530
+000533
+000536
+000541
+000542
+000543
+000545
+000546
+000548
+000551
+000554
+000555
+000558
+000559
+000560
+000561
+000564
+000566
+000567
+000568
+000569
+000571
+000572
+000581
+000583
+000588
+000589
+000590
+000591
+000595
+000600
+000601
+000604
+000610
+000611
+000612
+000613
+000614
+000615
+000618
+000619
+000620
+000624
+000625
+000626
+000628
+000630
+000634
+000635
+000636
+000639
+000642
+000644
+000645
+000647
+000648
+000650
+000655
+000657
+000658
+000659
+000660
+000667
+000669
+000670
+000674
+000677
+000679
+000682
+000683
+000684
+000691
+000692
+000694
+000696
+000698
+000699
+000700
+000702
+000704
+000706
+000708
+000716
+000717
+000718
+000721
+000722
+000725
+000727
+000728
+000729
+000731
+000734
+000736
+000737
+000740
+000741
+000745
+000746
+000748
+000750
+000751
+000752
+000754
+000756
+000761
+000765
+000766
+000767
+000768
+000769
+000771
+000772
+000773
+000774
+000778
+000779
+000782
+000790
+000792
+000795
+000798
+000800
+000801
+000802
+000803
+000804
+000805
+000806
+000807
+000809
+000810
+000811
+000812
+000816
+000819
+000823
+000826
+000831
+000837
+000838
+000840
+000841
+000843
+000844
+000847
+000848
+000849
+000850
+000852
+000854
+000859
+000862
+000863
+000869
+000873
+000874
+000875
+000876
+000877
+000878
+000879
+000881
+000884
+000885
+000889
+000893
+000894
+000897
+000899
+000904
+000907
+000909
+000911
+000912
+000915
+000916
+000917
+000920
+000922
+000923
+000926
+000928
+000930
+000931
+000932
+000938
+000939
+000940
+000942
+000943
+000944
+000948
+000949
+000952
+000953
+000956
+000958
+000961
+000963
+000964
+000966
+000967
+000969
+000970
+000971
+000973
+000974
+000976
+000979
+000981
+000983
+000984
+000985
+000986
+000988
+000991
+000999
+001002
+001006
+001007
+001008
+001010
+001011
+001012
+001013
+001014
+001015
+001018
+001019
+001021
+001022
+001025
+001026
+001027
+001035
+001037
+001039
+001042
+001043
+001046
+001050
+001051
+001053
+001054
+001055
+001058
+001063
+001065
+001066
+001067
+001068
+001069
+001070
+001071
+001075
+001076
+001077
+001078
+001083
+001084
+001086
+001088
+001089
+001094
+001095
+001096
+001097
+001099
+001101
+001102
+001104
+001106
+001107
+001108
+001111
+001113
+001114
+001115
+001116
+001118
+001120
+001123
+001125
+001127
+001129
+001131
+001132
+001133
+001134
+001135
+001136
+001138
+001139
+001140
+001141
+001143
+001144
+001145
+001147
+001148
+001149
+001150
+001152
+001153
+001154
+001155
+001158
+001162
+001163
+001167
+001172
+001173
+001176
+001177
+001178
+001179
+001180
+001182
+001183
+001187
+001188
+001189
+001191
+001192
+001193
+001194
+001195
+001198
+001199
+001203
+001206
+001207
+001213
+001214
+001216
+001217
+001218
+001221
+001222
+001224
+001225
+001226
+001228
+001230
+001232
+001234
+001235
+001236
+001237
+001239
+001241
+001242
+001243
+001244
+001245
+001246
+001249
+001251
+001252
+001253
+001254
+001255
+001257
+001259
+001260
+001261
+001263
+001265
+001266
+001267
+001268
+001269
+001270
+001271
+001272
+001273
+001274
+001275
+001281
+001284
+001286
+001287
+001289
+001291
+001292
+001294
+001295
+001296
+001303
+001304
+001305
+001306
+001307
+001308
+001314
+001317
+001318
+001329
+001330
+001331
+001332
+001333
+001334
+001336
+001337
+001339
+001342
+001344
+001345
+001346
+001347
+001350
+001352
+001353
+001355
+001356
+001359
+001363
+001365
+001372
+001374
+001375
+001376
+001377
+001380
+001381
+001382
+001384
+001386
+001387
+001388
+001389
+001391
+001395
+001397
+001398
+001407
+001410
+001411
+001412
+001415
+001416
+001419
+001421
+001424
+001427
+001431
+001432
+001435
+001437
+001438
+001439
+001441
+001442
+001443
+001445
+001446
+001448
+001450
+001451
+001458
+001461
+001463
+001466
+001469
+001471
+001477
+001478
+001480
+001481
+001485
+001487
+001488
+001489
+001495
+001497
+001501
+001502
+001507
+001508
+001511
+001513
+001514
+001516
+001517
+001521
+001522
+001524
+001525
+001526
+001527
+001528
+001533
+001535
+001536
+001537
+001538
+001542
+001545
+001546
+001547
+001549
+001552
+001555
+001557
+001560
+001562
+001564
+001565
+001567
+001569
+001573
+001574
+001576
+001577
+001579
+001582
+001583
+001585
+001586
+001587
+001588
+001589
+001590
+001591
+001592
+001594
+001596
+001597
+001600
+001602
+001603
+001605
+001606
+001610
+001613
+001615
+001616
+001617
+001619
+001621
+001625
+001627
+001629
+001631
+001633
+001634
+001635
+001640
+001643
+001645
+001647
+001650
+001654
+001656
+001658
+001660
+001662
+001664
+001665
+001666
+001667
+001670
+001675
+001680
+001682
+001683
+001684
+001689
+001693
+001694
+001697
+001699
+001701
+001702
+001704
+001705
+001706
+001707
+001709
+001710
+001711
+001712
+001713
+001714
+001717
+001718
+001719
+001721
+001722
+001726
+001727
+001729
+001732
+001733
+001740
+001741
+001742
+001745
+001746
+001749
+001750
+001751
+001752
+001755
+001758
+001762
+001764
+001765
+001768
+001771
+001772
+001774
+001776
+001778
+001780
+001781
+001782
+001783
+001786
+001787
+001794
+001795
+001797
+001800
+001801
+001802
+001804
+001807
+001808
+001813
+001814
+001817
+001818
+001820
+001822
+001823
+001824
+001825
+001828
+001831
+001835
+001840
+001844
+001846
+001848
+001851
+001852
+001853
+001854
+001855
+001856
+001858
+001859
+001861
+001862
+001863
+001867
+001868
+001869
+001872
+001875
+001877
+001878
+001880
+001881
+001884
+001885
+001886
+001887
+001888
+001890
+001892
+001893
+001897
+001898
+001900
+001904
+001905
+001909
+001919
+001920
+001923
+001924
+001925
+001926
+001927
+001928
+001929
+001931
+001932
+001933
+001934
+001936
+001937
+001940
+001941
+001942
+001943
+001945
+001946
+001952
+001954
+001959
+001960
+001966
+001967
+001969
+001972
+001977
+001978
+001979
+001980
+001982
+001983
+001984
+001985
+001986
+001989
+001991
+001995
+001996
+001997
+001999
+002000
+002001
+002002
+002004
+002008
+002010
+002011
+002012
+002013
+002014
+002017
+002019
+002021
+002022
+002025
+002027
+002028
+002029
+002034
+002035
+002036
+002037
+002038
+002042
+002043
+002044
+002045
+002046
+002048
+002049
+002050
+002052
+002054
+002056
+002057
+002058
+002062
+002068
+002071
+002073
+002074
+002075
+002076
+002078
+002079
+002081
+002082
+002085
+002086
+002087
+002089
+002091
+002093
+002094
+002100
+002101
+002102
+002103
+002107
+002108
+002111
+002112
+002113
+002115
+002118
+002120
+002121
+002123
+002124
+002127
+002128
+002130
+002131
+002135
+002136
+002137
+002138
+002139
+002140
+002142
+002151
+002152
+002153
+002158
+002159
+002160
+002161
+002163
+002165
+002166
+002168
+002169
+002170
+002173
+002177
+002179
+002182
+002183
+002185
+002187
+002188
+002193
+002196
+002200
+002201
+002202
+002206
+002207
+002209
+002215
+002216
+002218
+002219
+002220
+002224
+002225
+002228
+002229
+002232
+002233
+002234
+002239
+002243
+002245
+002246
+002248
+002250
+002251
+002254
+002255
+002257
+002258
+002260
+002262
+002266
+002272
+002276
+002277
+002279
+002280
+002282
+002283
+002284
+002286
+002287
+002290
+002291
+002292
+002293
+002294
+002295
+002298
+002299
+002300
+002303
+002304
+002306
+002307
+002308
+002310
+002314
+002315
+002319
+002320
+002325
+002327
+002329
+002330
+002332
+002334
+002336
+002337
+002338
+002340
+002341
+002344
+002345
+002346
+002347
+002348
+002353
+002356
+002357
+002359
+002362
+002365
+002366
+002367
+002369
+002370
+002372
+002376
+002378
+002380
+002382
+002383
+002384
+002385
+002386
+002387
+002391
+002392
+002393
+002397
+002398
+002399
+002404
+002405
+002411
+002414
+002415
+002418
+002419
+002420
+002422
+002423
+002424
+002425
+002428
+002429
+002432
+002433
+002434
+002439
+002440
+002442
+002446
+002450
+002454
+002455
+002457
+002458
+002460
+002461
+002462
+002463
+002473
+002474
+002476
+002477
+002478
+002479
+002483
+002486
+002488
+002490
+002492
+002495
+002497
+002499
+002500
+002502
+002503
+002504
+002505
+002506
+002509
+002511
+002516
+002519
+002520
+002521
+002525
+002526
+002528
+002529
+002530
+002531
+002532
+002534
+002538
+002539
+002540
+002541
+002543
+002546
+002548
+002552
+002556
+002557
+002558
+002562
+002563
+002564
+002565
+002568
+002569
+002570
+002572
+002574
+002575
+002577
+002580
+002581
+002583
+002584
+002585
+002586
+002590
+002594
+002598
+002599
+002600
+002601
+002602
+002603
+002604
+002606
+002612
+002613
+002615
+002619
+002621
+002625
+002626
+002628
+002630
+002631
+002633
+002635
+002636
+002638
+002640
+002641
+002644
+002645
+002646
+002651
+002653
+002656
+002657
+002661
+002663
+002666
+002669
+002673
+002674
+002675
+002677
+002680
+002681
+002685
+002686
+002690
+002692
+002693
+002694
+002695
+002696
+002699
+002702
+002706
+002707
+002709
+002710
+002711
+002712
+002713
+002715
+002717
+002720
+002721
+002722
+002724
+002725
+002726
+002727
+002728
+002729
+002730
+002735
+002737
+002740
+002742
+002744
+002745
+002746
+002747
+002748
+002749
+002752
+002753
+002755
+002757
+002758
+002760
+002761
+002763
+002764
+002765
+002767
+002772
+002773
+002775
+002783
+002786
+002787
+002789
+002793
+002794
+002796
+002797
+002800
+002801
+002804
+002805
+002806
+002809
+002810
+002811
+002812
+002814
+002815
+002818
+002820
+002826
+002827
+002828
+002830
+002831
+002833
+002836
+002839
+002840
+002841
+002844
+002845
+002846
+002847
+002848
+002853
+002856
+002858
+002861
+002863
+002866
+002867
+002875
+002876
+002877
+002878
+002879
+002880
+002881
+002883
+002885
+002889
+002890
+002891
+002892
+002893
+002894
+002895
+002896
+002900
+002901
+002902
+002903
+002905
+002908
+002911
+002914
+002916
+002917
+002919
+002924
+002925
+002928
+002930
+002934
+002935
+002937
+002942
+002944
+002945
+002947
+002948
+002951
+002953
+002955
+002957
+002958
+002959
+002960
+002961
+002962
+002963
+002964
+002966
+002971
+002974
+002976
+002977
+002978
+002979
+002982
+002984
+002985
+002988
+002991
+002993
+002994
+002995
+002997
+002999
+003000
+003001
+003003
+003004
+003005
+003006
+003007
+003010
+003011
+003019
+003022
+003024
+003025
+003027
+003029
+003030
+003031
+003032
+003033
+003034
+003035
+003038
+003042
+003043
+003046
+003047
+003048
+003050
+003052
+003053
+003054
+003055
+003056
+003058
+003061
+003062
+003065
+003066
+003067
+003071
+003073
+003074
+003076
+003080
+003082
+003087
+003088
+003090
+003094
+003096
+003099
+003101
+003102
+003103
+003106
+003107
+003109
+003110
+003112
+003114
+003116
+003118
+003124
+003126
+003127
+003129
+003131
+003133
+003134
+003135
+003136
+003137
+003141
+003142
+003144
+003145
+003146
+003148
+003150
+003153
+003156
+003159
+003161
+003162
+003165
+003167
+003170
+003172
+003174
+003175
+003177
+003179
+003180
+003181
+003182
+003183
+003187
+003190
+003192
+003194
+003197
+003199
+003202
+003203
+003204
+003207
+003210
+003211
+003214
+003216
+003217
+003219
+003221
+003222
+003224
+003225
+003226
+003228
+003229
+003231
+003232
+003233
+003236
+003239
+003240
+003242
+003247
+003250
+003251
+003252
+003254
+003255
+003257
+003259
+003265
+003266
+003269
+003272
+003275
+003276
+003280
+003281
+003283
+003288
+003292
+003295
+003296
+003298
+003300
+003301
+003302
+003304
+003305
+003306
+003308
+003310
+003312
+003313
+003315
+003316
+003318
+003319
+003322
+003323
+003324
+003325
+003330
+003331
+003337
+003338
+003341
+003343
+003346
+003347
+003350
+003351
+003352
+003353
+003355
+003357
+003358
+003364
+003365
+003366
+003367
+003368
+003370
+003373
+003375
+003379
+003385
+003386
+003393
+003394
+003395
+003396
+003397
+003399
+003401
+003402
+003403
+003404
+003405
+003406
+003407
+003408
+003409
+003410
+003411
+003412
+003417
+003419
+003421
+003422
+003425
+003426
+003428
+003429
+003430
+003432
+003434
+003435
+003443
+003447
+003448
+003449
+003450
+003453
+003456
+003461
+003464
+003465
+003466
+003467
+003469
+003470
+003471
+003474
+003478
+003480
+003481
+003482
+003483
+003484
+003487
+003488
+003489
+003490
+003491
+003492
+003495
+003496
+003497
+003502
+003503
+003504
+003506
+003511
+003515
+003517
+003519
+003520
+003521
+003524
+003527
+003528
+003529
+003530
+003531
+003535
+003539
+003543
+003544
+003547
+003550
+003552
+003553
+003554
+003557
+003558
+003559
+003562
+003563
+003568
+003571
+003573
+003574
+003580
+003582
+003583
+003584
+003588
+003600
+003601
+003604
+003605
+003607
+003608
+003609
+003611
+003614
+003616
+003618
+003620
+003621
+003622
+003623
+003624
+003627
+003629
+003630
+003631
+003632
+003633
+003634
+003635
+003643
+003645
+003647
+003649
+003652
+003653
+003655
+003658
+003659
+003661
+003662
+003667
+003668
+003669
+003671
+003676
+003677
+003678
+003679
+003682
+003683
+003684
+003688
+003689
+003690
+003691
+003692
+003702
+003703
+003705
+003707
+003708
+003711
+003712
+003715
+003716
+003718
+003719
+003723
+003726
+003728
+003735
+003736
+003737
+003738
+003739
+003746
+003747
+003748
+003750
+003751
+003753
+003755
+003756
+003762
+003763
+003764
+003769
+003771
+003775
+003777
+003778
+003779
+003781
+003782
+003787
+003788
+003793
+003794
+003798
+003800
+003802
+003804
+003805
+003807
+003808
+003809
+003811
+003812
+003814
+003820
+003822
+003826
+003827
+003828
+003830
+003834
+003835
+003837
+003841
+003847
+003852
+003854
+003856
+003859
+003860
+003864
+003866
+003869
+003870
+003872
+003873
+003874
+003878
+003879
+003880
+003881
+003883
+003885
+003886
+003890
+003891
+003892
+003894
+003897
+003898
+003899
+003901
+003902
+003905
+003907
+003909
+003914
+003915
+003916
+003920
+003923
+003924
+003926
+003931
+003932
+003934
+003937
+003938
+003943
+003945
+003946
+003948
+003950
+003956
+003958
+003961
+003962
+003964
+003965
+003969
+003970
+003972
+003975
+003977
+003980
+003981
+003982
+003984
+003986
+003992
+003996
+003998
+004000
+004001
+004002
+004003
+004004
+004007
+004008
+004009
+004010
+004011
+004016
+004021
+004026
+004027
+004028
+004032
+004033
+004034
+004036
+004038
+004040
+004041
+004042
+004045
+004048
+004049
+004051
+004055
+004059
+004061
+004063
+004064
+004065
+004068
+004072
+004074
+004077
+004079
+004081
+004082
+004083
+004085
+004087
+004089
+004091
+004092
+004095
+004096
+004098
+004100
+004101
+004104
+004105
+004107
+004108
+004109
+004110
+004111
+004113
+004116
+004117
+004118
+004119
+004120
+004121
+004122
+004124
+004125
+004126
+004128
+004129
+004130
+004131
+004132
+004136
+004137
+004138
+004140
+004142
+004143
+004148
+004149
+004150
+004152
+004153
+004154
+004155
+004156
+004157
+004158
+004160
+004161
+004162
+004163
+004164
+004168
+004171
+004172
+004173
+004174
+004175
+004185
+004187
+004188
+004189
+004190
+004191
+004195
+004196
+004202
+004205
+004206
+004207
+004209
+004210
+004213
+004214
+004215
+004220
+004221
+004222
+004223
+004224
+004226
+004228
+004232
+004237
+004239
+004241
+004242
+004243
+004246
+004248
+004249
+004250
+004251
+004254
+004255
+004256
+004259
+004260
+004263
+004270
+004271
+004275
+004277
+004278
+004280
+004281
+004282
+004284
+004285
+004288
+004289
+004290
+004291
+004293
+004294
+004295
+004298
+004299
+004300
+004301
+004303
+004305
+004306
+004307
+004309
+004311
+004312
+004314
+004318
+004319
+004321
+004323
+004324
+004326
+004327
+004329
+004330
+004335
+004336
+004337
+004338
+004340
+004342
+004343
+004345
+004348
+004349
+004350
+004352
+004353
+004360
+004362
+004363
+004364
+004367
+004368
+004369
+004370
+004373
+004374
+004377
+004383
+004384
+004385
+004388
+004391
+004392
+004393
+004396
+004397
+004398
+004401
+004402
+004403
+004404
+004406
+004407
+004414
+004415
+004418
+004419
+004420
+004421
+004422
+004423
+004424
+004425
+004426
+004429
+004430
+004433
+004434
+004435
+004437
+004438
+004439
+004440
+004443
+004444
+004447
+004450
+004452
+004454
+004456
+004458
+004460
+004462
+004465
+004469
+004470
+004472
+004474
+004475
+004480
+004481
+004482
+004483
+004485
+004486
+004487
+004489
+004490
+004491
+004493
+004494
+004496
+004501
+004502
+004508
+004511
+004513
+004516
+004517
+004519
+004520
+004521
+004526
+004527
+004528
+004529
+004530
+004531
+004532
+004534
+004540
+004541
+004542
+004547
+004548
+004549
+004551
+004553
+004556
+004557
+004562
+004566
+004567
+004568
+004569
+004570
+004573
+004574
+004576
+004578
+004581
+004582
+004585
+004587
+004588
+004589
+004591
+004596
+004598
+004599
+004603
+004608
+004609
+004610
+004611
+004612
+004615
+004618
+004620
+004622
+004624
+004626
+004629
+004630
+004632
+004633
+004634
+004636
+004638
+004640
+004644
+004647
+004648
+004649
+004650
+004651
+004652
+004655
+004657
+004658
+004660
+004665
+004666
+004667
+004668
+004669
+004672
+004673
+004679
+004680
+004682
+004683
+004685
+004686
+004687
+004688
+004689
+004691
+004692
+004693
+004694
+004695
+004697
+004698
+004699
+004700
+004705
+004706
+004708
+004709
+004710
+004711
+004713
+004714
+004715
+004716
+004717
+004718
+004720
+004721
+004722
+004724
+004725
+004726
+004730
+004732
+004734
+004735
+004737
+004738
+004739
+004740
+004742
+004743
+004744
+004745
+004746
+004748
+004752
+004753
+004756
+004759
+004762
+004763
+004764
+004766
+004768
+004769
+004770
+004773
+004776
+004777
+004782
+004783
+004787
+004788
+004790
+004791
+004792
+004797
+004799
+004800
+004804
+004806
+004807
+004810
+004811
+004813
+004814
+004815
+004816
+004817
+004821
+004822
+004825
+004829
+004830
+004831
+004832
+004835
+004839
+004843
+004846
+004848
+004849
+004850
+004851
+004852
+004858
+004859
+004860
+004861
+004862
+004863
+004864
+004867
+004868
+004871
+004873
+004874
+004875
+004881
+004885
+004887
+004888
+004891
+004892
+004893
+004895
+004896
+004898
+004902
+004903
+004904
+004905
+004907
+004909
+004914
+004917
+004918
+004920
+004921
+004924
+004926
+004927
+004928
+004929
+004931
+004932
+004934
+004935
+004938
+004941
+004942
+004943
+004944
+004946
+004947
+004948
+004949
+004953
+004954
+004956
+004958
+004959
+004960
+004962
+004963
+004966
+004974
+004976
+004979
+004981
+004983
+004985
+004986
+004988
+004989
+004990
+004993
+004994
+004995
+004996
+004998
+004999
+005001
+005002
+005004
+005008
+005010
+005013
+005014
+005015
+005017
+005019
+005021
+005024
+005026
+005028
+005032
+005034
+005036
+005037
+005038
+005040
+005041
+005045
+005049
+005050
+005052
+005053
+005054
+005055
+005056
+005057
+005058
+005062
+005063
+005064
+005065
+005067
+005068
+005070
+005072
+005073
+005074
+005075
+005077
+005078
+005079
+005080
+005081
+005082
+005086
+005090
+005093
+005094
+005095
+005101
+005103
+005105
+005108
+005109
+005110
+005112
+005113
+005120
+005121
+005122
+005124
+005125
+005127
+005128
+005133
+005135
+005136
+005138
+005139
+005140
+005141
+005143
+005144
+005145
+005147
+005149
+005153
+005155
+005156
+005157
+005158
+005161
+005162
+005163
+005164
+005166
+005167
+005168
+005170
+005172
+005174
+005175
+005176
+005179
+005180
+005181
+005182
+005184
+005185
+005188
+005189
+005190
+005191
+005194
+005197
+005198
+005199
+005201
+005206
+005213
+005214
+005217
+005218
+005219
+005221
+005222
+005226
+005227
+005229
+005230
+005233
+005234
+005236
+005237
+005240
+005241
+005242
+005244
+005246
+005249
+005251
+005255
+005256
+005260
+005262
+005267
+005268
+005271
+005273
+005274
+005275
+005276
+005279
+005280
+005282
+005284
+005287
+005289
+005292
+005296
+005297
+005298
+005299
+005304
+005307
+005308
+005309
+005311
+005312
+005313
+005315
+005316
+005318
+005319
+005321
+005322
+005323
+005325
+005328
+005329
+005330
+005333
+005334
+005335
+005336
+005337
+005338
+005341
+005342
+005343
+005345
+005347
+005349
+005350
+005359
+005360
+005363
+005365
+005366
+005368
+005369
+005371
+005372
+005375
+005377
+005378
+005379
+005381
+005385
+005386
+005389
+005390
+005391
+005404
+005405
+005413
+005415
+005422
+005423
+005426
+005427
+005429
+005430
+005431
+005434
+005437
+005441
+005443
+005444
+005445
+005447
+005448
+005449
+005450
+005452
+005453
+005458
+005459
+005460
+005461
+005465
+005466
+005467
+005471
+005472
+005473
+005474
+005476
+005477
+005479
+005481
+005482
+005484
+005486
+005487
+005489
+005494
+005495
+005498
+005505
+005510
+005511
+005514
+005515
+005523
+005525
+005528
+005531
+005532
+005534
+005536
+005538
+005540
+005542
+005544
+005545
+005546
+005551
+005552
+005555
+005556
+005557
+005558
+005559
+005560
+005565
+005566
+005570
+005571
+005572
+005573
+005576
+005577
+005580
+005581
+005582
+005584
+005586
+005587
+005588
+005589
+005590
+005595
+005596
+005600
+005601
+005602
+005603
+005610
+005613
+005616
+005617
+005618
+005619
+005623
+005625
+005630
+005631
+005633
+005634
+005635
+005638
+005639
+005640
+005642
+005643
+005649
+005650
+005652
+005653
+005656
+005658
+005659
+005660
+005662
+005664
+005668
+005669
+005672
+005673
+005676
+005677
+005680
+005683
+005685
+005687
+005689
+005695
+005698
+005699
+005700
+005703
+005704
+005706
+005707
+005708
+005709
+005712
+005713
+005714
+005717
+005724
+005725
+005727
+005728
+005729
+005731
+005735
+005736
+005739
+005740
+005741
+005743
+005744
+005745
+005746
+005747
+005751
+005754
+005757
+005760
+005762
+005763
+005765
+005777
+005782
+005783
+005784
+005785
+005786
+005787
+005790
+005793
+005794
+005796
+005800
+005801
+005803
+005805
+005806
+005807
+005811
+005812
+005818
+005819
+005820
+005821
+005822
+005826
+005827
+005829
+005834
+005839
+005840
+005841
+005843
+005852
+005854
+005855
+005856
+005857
+005859
+005864
+005869
+005873
+005876
+005878
+005879
+005881
+005882
+005883
+005885
+005887
+005889
+005892
+005893
+005894
+005899
+005900
+005901
+005903
+005905
+005906
+005907
+005909
+005910
+005911
+005912
+005913
+005914
+005916
+005917
+005918
+005919
+005921
+005922
+005923
+005925
+005926
+005927
+005931
+005933
+005935
+005938
+005939
+005944
+005947
+005948
+005949
+005952
+005955
+005958
+005961
+005962
+005963
+005965
+005969
+005970
+005972
+005975
+005978
+005981
+005982
+005984
+005985
+005986
+005988
+005994
+005996
+005997
+005999
+006001
+006002
+006003
+006005
+006008
+006009
+006010
+006012
+006013
+006014
+006016
+006023
+006024
+006026
+006027
+006028
+006029
+006030
+006031
+006033
+006034
+006036
+006038
+006039
+006041
+006042
+006043
+006044
+006045
+006046
+006047
+006048
+006050
+006052
+006054
+006057
+006058
+006060
+006061
+006062
+006063
+006066
+006067
+006068
+006070
+006071
+006074
+006075
+006077
+006078
+006083
+006085
+006086
+006087
+006088
+006093
+006095
+006096
+006097
+006098
+006100
+006102
+006103
+006106
+006107
+006110
+006114
+006115
+006116
+006117
+006118
+006121
+006122
+006123
+006125
+006126
+006127
+006130
+006133
+006136
+006139
+006144
+006146
+006148
+006151
+006152
+006154
+006156
+006161
+006163
+006165
+006167
+006168
+006169
+006173
+006176
+006177
+006182
+006185
+006186
+006187
+006190
+006194
+006195
+006196
+006198
+006202
+006204
+006208
+006210
+006213
+006215
+006219
+006222
+006227
+006228
+006229
+006232
+006233
+006238
+006240
+006244
+006246
+006247
+006249
+006250
+006258
+006263
+006265
+006266
+006267
+006269
+006270
+006272
+006273
+006274
+006275
+006276
+006278
+006280
+006282
+006286
+006287
+006288
+006297
+006300
+006301
+006302
+006305
+006306
+006312
+006314
+006315
+006316
+006317
+006321
+006322
+006324
+006331
+006332
+006333
+006334
+006338
+006339
+006340
+006342
+006343
+006344
+006345
+006348
+006349
+006351
+006353
+006354
+006355
+006356
+006357
+006360
+006364
+006366
+006368
+006369
+006370
+006371
+006372
+006377
+006379
+006380
+006381
+006385
+006386
+006388
+006391
+006393
+006394
+006395
+006396
+006403
+006405
+006406
+006407
+006409
+006410
+006411
+006415
+006416
+006417
+006420
+006423
+006424
+006425
+006426
+006427
+006433
+006434
+006435
+006436
+006437
+006439
+006440
+006441
+006442
+006444
+006445
+006446
+006451
+006452
+006453
+006454
+006462
+006464
+006465
+006468
+006469
+006470
+006472
+006473
+006474
+006475
+006477
+006478
+006481
+006482
+006483
+006484
+006486
+006488
+006491
+006493
+006496
+006497
+006498
+006503
+006505
+006506
+006507
+006508
+006512
+006514
+006515
+006516
+006517
+006519
+006520
+006521
+006524
+006525
+006529
+006530
+006531
+006532
+006533
+006534
+006535
+006537
+006540
+006542
+006548
+006549
+006551
+006553
+006555
+006556
+006558
+006560
+006561
+006563
+006565
+006568
+006569
+006570
+006574
+006576
+006577
+006578
+006581
+006582
+006583
+006586
+006588
+006590
+006592
+006593
+006595
+006596
+006597
+006602
+006603
+006604
+006611
+006612
+006613
+006614
+006618
+006623
+006624
+006625
+006626
+006628
+006629
+006632
+006633
+006634
+006636
+006637
+006638
+006641
+006643
+006647
+006649
+006650
+006651
+006655
+006656
+006658
+006659
+006660
+006664
+006666
+006667
+006669
+006670
+006674
+006676
+006677
+006678
+006679
+006682
+006685
+006686
+006692
+006693
+006694
+006695
+006696
+006698
+006701
+006703
+006709
+006710
+006711
+006712
+006713
+006714
+006715
+006719
+006720
+006723
+006725
+006726
+006729
+006731
+006732
+006733
+006734
+006737
+006738
+006741
+006744
+006745
+006747
+006751
+006752
+006753
+006754
+006755
+006756
+006758
+006759
+006760
+006761
+006762
+006764
+006765
+006767
+006768
+006770
+006771
+006772
+006773
+006777
+006778
+006780
+006781
+006782
+006783
+006785
+006786
+006789
+006791
+006792
+006794
+006796
+006797
+006798
+006800
+006803
+006804
+006806
+006807
+006808
+006811
+006812
+006813
+006815
+006816
+006818
+006819
+006822
+006828
+006829
+006832
+006833
+006836
+006837
+006841
+006843
+006844
+006847
+006849
+006850
+006852
+006853
+006854
+006855
+006856
+006858
+006860
+006862
+006863
+006866
+006868
+006870
+006872
+006873
+006874
+006876
+006879
+006881
+006882
+006884
+006885
+006887
+006889
+006891
+006895
+006897
+006898
+006899
+006900
+006901
+006903
+006906
+006907
+006908
+006910
+006913
+006914
+006917
+006922
+006925
+006928
+006930
+006936
+006937
+006938
+006942
+006943
+006944
+006945
+006948
+006950
+006953
+006954
+006955
+006956
+006959
+006960
+006962
+006964
+006968
+006971
+006973
+006977
+006978
+006980
+006981
+006982
+006987
+006989
+006990
+006992
+006994
+006997
+006999
+007000
+007003
+007005
+007006
+007008
+007010
+007011
+007012
+007014
+007015
+007016
+007019
+007022
+007023
+007026
+007027
+007028
+007029
+007030
+007031
+007032
+007033
+007034
+007037
+007038
+007042
+007043
+007047
+007048
+007049
+007052
+007053
+007055
+007056
+007059
+007061
+007063
+007065
+007067
+007068
+007069
+007071
+007072
+007074
+007076
+007078
+007079
+007080
+007081
+007082
+007083
+007084
+007085
+007087
+007088
+007089
+007091
+007095
+007098
+007100
+007103
+007109
+007110
+007112
+007115
+007117
+007119
+007120
+007122
+007125
+007130
+007131
+007132
+007133
+007135
+007136
+007138
+007139
+007144
+007145
+007146
+007149
+007154
+007157
+007158
+007161
+007162
+007163
+007164
+007165
+007166
+007168
+007169
+007172
+007174
+007176
+007177
+007178
+007180
+007182
+007183
+007187
+007194
+007198
+007199
+007200
+007201
+007202
+007204
+007205
+007207
+007208
+007210
+007212
+007214
+007215
+007217
+007219
+007221
+007225
+007227
+007229
+007230
+007232
+007233
+007235
+007238
+007240
+007242
+007244
+007246
+007247
+007252
+007253
+007255
+007256
+007258
+007260
+007261
+007262
+007265
+007266
+007267
+007271
+007272
+007273
+007274
+007275
+007277
+007278
+007279
+007280
+007283
+007284
+007287
+007288
+007289
+007290
+007291
+007292
+007294
+007299
+007300
+007302
+007303
+007304
+007309
+007310
+007311
+007315
+007318
+007319
+007322
+007323
+007325
+007326
+007327
+007329
+007330
+007331
+007336
+007337
+007339
+007342
+007343
+007344
+007345
+007347
+007349
+007350
+007351
+007352
+007353
+007359
+007360
+007364
+007369
+007371
+007374
+007375
+007376
+007377
+007380
+007381
+007382
+007383
+007384
+007385
+007389
+007391
+007395
+007396
+007397
+007398
+007401
+007402
+007403
+007405
+007407
+007409
+007410
+007411
+007412
+007413
+007415
+007416
+007419
+007420
+007421
+007422
+007423
+007424
+007426
+007430
+007433
+007434
+007435
+007436
+007437
+007439
+007440
+007442
+007445
+007447
+007448
+007449
+007450
+007453
+007456
+007458
+007462
+007463
+007464
+007466
+007467
+007468
+007469
+007470
+007473
+007475
+007477
+007478
+007480
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/__init__.py b/notebooks/3D-point-pillars/pointpillars/dataset/__init__.py
new file mode 100644
index 00000000000..acbeb69b922
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/__init__.py
@@ -0,0 +1,3 @@
+from .data_aug import point_range_filter, data_augment
+from .kitti import Kitti
+from .dataloader import get_dataloader
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/data_aug.py b/notebooks/3D-point-pillars/pointpillars/dataset/data_aug.py
new file mode 100644
index 00000000000..2c7be63abc3
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/data_aug.py
@@ -0,0 +1,357 @@
+import copy
+import numba
+import numpy as np
+import os
+import pdb
+from pointpillars.utils import bbox3d2bevcorners, box_collision_test, read_points, \
+ remove_pts_in_bboxes, limit_period
+
+
+def dbsample(CLASSES, data_root, data_dict, db_sampler, sample_groups):
+ '''
+ CLASSES: dict(Pedestrian=0, Cyclist=1, Car=2)
+ data_root: str, data root
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ db_infos: dict(Pedestrian, Cyclist, Car, ...)
+ return: data_dict
+ '''
+ pts, gt_bboxes_3d = data_dict['pts'], data_dict['gt_bboxes_3d']
+ gt_labels, gt_names = data_dict['gt_labels'], data_dict['gt_names']
+ gt_difficulty = data_dict['difficulty']
+ image_info, calib_info = data_dict['image_info'], data_dict['calib_info']
+
+ sampled_pts, sampled_names, sampled_labels = [], [], []
+ sampled_bboxes, sampled_difficulty = [], []
+
+ avoid_coll_boxes = copy.deepcopy(gt_bboxes_3d)
+ for name, v in sample_groups.items():
+ # 1. calculate sample numbers
+ sampled_num = v - np.sum(gt_names == name)
+ if sampled_num <= 0:
+ continue
+
+ # 2. sample databases bboxes
+ sampled_cls_list = db_sampler[name].sample(sampled_num)
+ sampled_cls_bboxes = np.array([item['box3d_lidar'] for item in sampled_cls_list], dtype=np.float32)
+
+ # 3. box_collision_test
+ avoid_coll_boxes_bv_corners = bbox3d2bevcorners(avoid_coll_boxes)
+ sampled_cls_bboxes_bv_corners = bbox3d2bevcorners(sampled_cls_bboxes)
+ coll_query_matrix = np.concatenate([avoid_coll_boxes_bv_corners, sampled_cls_bboxes_bv_corners], axis=0)
+ coll_mat = box_collision_test(coll_query_matrix, coll_query_matrix)
+ n_gt, tmp_bboxes = len(avoid_coll_boxes_bv_corners), []
+ for i in range(n_gt, len(coll_mat)):
+ if any(coll_mat[i]):
+ coll_mat[i] = False
+ coll_mat[:, i] = False
+ else:
+ cur_sample = sampled_cls_list[i - n_gt]
+ pt_path = os.path.join(data_root, cur_sample['path'])
+ sampled_pts_cur = read_points(pt_path)
+ sampled_pts_cur[:, :3] += cur_sample['box3d_lidar'][:3]
+ sampled_pts.append(sampled_pts_cur)
+ sampled_names.append(cur_sample['name'])
+ sampled_labels.append(CLASSES[cur_sample['name']])
+ sampled_bboxes.append(cur_sample['box3d_lidar'])
+ tmp_bboxes.append(cur_sample['box3d_lidar'])
+ sampled_difficulty.append(cur_sample['difficulty'])
+ if len(tmp_bboxes) == 0:
+ tmp_bboxes = np.array(tmp_bboxes).reshape(-1, 7)
+ else:
+ tmp_bboxes = np.array(tmp_bboxes)
+ avoid_coll_boxes = np.concatenate([avoid_coll_boxes, tmp_bboxes], axis=0)
+
+ # merge sampled database
+ # remove raw points in sampled_bboxes firstly
+ pts = remove_pts_in_bboxes(pts, np.stack(sampled_bboxes, axis=0))
+ # pts = np.concatenate([pts, np.concatenate(sampled_pts, axis=0)], axis=0)
+ pts = np.concatenate([np.concatenate(sampled_pts, axis=0), pts], axis=0)
+ gt_bboxes_3d = avoid_coll_boxes.astype(np.float32)
+ gt_labels = np.concatenate([gt_labels, np.array(sampled_labels)], axis=0)
+ gt_names = np.concatenate([gt_names, np.array(sampled_names)], axis=0)
+ difficulty = np.concatenate([gt_difficulty, np.array(sampled_difficulty)], axis=0)
+ data_dict = {
+ 'pts': pts,
+ 'gt_bboxes_3d': gt_bboxes_3d,
+ 'gt_labels': gt_labels,
+ 'gt_names': gt_names,
+ 'difficulty': difficulty,
+ 'image_info': image_info,
+ 'calib_info': calib_info
+ }
+ return data_dict
+
+
+@numba.jit(nopython=True)
+def object_noise_core(pts, gt_bboxes_3d, bev_corners, trans_vec, rot_angle, rot_mat, masks):
+ '''
+ pts: (N, 4)
+ gt_bboxes_3d: (n_bbox, 7)
+ bev_corners: ((n_bbox, 4, 2))
+ trans_vec: (n_bbox, num_try, 3)
+ rot_mat: (n_bbox, num_try, 2, 2)
+ masks: (N, n_bbox), bool
+ return: gt_bboxes_3d, pts
+ '''
+ # 1. select the noise of num_try for each bbox under the collision test
+ n_bbox, num_try = trans_vec.shape[:2]
+
+ # succ_mask: (n_bbox, ), whether each bbox can be added noise successfully. -1 denotes failure.
+ succ_mask = -np.ones((n_bbox, ), dtype=np.int_)
+ for i in range(n_bbox):
+ for j in range(num_try):
+ cur_bbox = bev_corners[i] - np.expand_dims(gt_bboxes_3d[i, :2], 0) # (4, 2) - (1, 2) -> (4, 2)
+ rot = np.zeros((2, 2), dtype=np.float32)
+ rot[:] = rot_mat[i, j] # (2, 2)
+ trans = trans_vec[i, j] # (3, )
+ cur_bbox = cur_bbox @ rot
+ cur_bbox += gt_bboxes_3d[i, :2]
+ cur_bbox += np.expand_dims(trans[:2], 0) # (4, 2)
+ coll_mat = box_collision_test(np.expand_dims(cur_bbox, 0), bev_corners)
+ coll_mat[0, i] = False
+ if coll_mat.any():
+ continue
+ else:
+ bev_corners[i] = cur_bbox # update the bev_corners when adding noise succseefully.
+ succ_mask[i] = j
+ break
+ # 2. points and bboxes noise
+ visit = {}
+ for i in range(n_bbox):
+ jj = succ_mask[i]
+ if jj == -1:
+ continue
+ cur_trans, cur_angle = trans_vec[i, jj], rot_angle[i, jj]
+ cur_rot_mat = np.zeros((2, 2), dtype=np.float32)
+ cur_rot_mat[:] = rot_mat[i, jj]
+ for k in range(len(pts)):
+ if masks[k][i] and k not in visit:
+ cur_pt = pts[k] # (4, )
+ cur_pt_xyz = np.zeros((1, 3), dtype=np.float32)
+ cur_pt_xyz[0] = cur_pt[:3] - gt_bboxes_3d[i][:3]
+ tmp_cur_pt_xy = np.zeros((1, 2), dtype=np.float32)
+ tmp_cur_pt_xy[:] = cur_pt_xyz[:, :2]
+ cur_pt_xyz[:, :2] = tmp_cur_pt_xy @ cur_rot_mat # (1, 2)
+ cur_pt_xyz[0] = cur_pt_xyz[0] + gt_bboxes_3d[i][:3]
+ cur_pt_xyz[0] = cur_pt_xyz[0] + cur_trans[:3]
+ cur_pt[:3] = cur_pt_xyz[0]
+ visit[k] = 1
+
+ gt_bboxes_3d[i, :3] += cur_trans[:3]
+ gt_bboxes_3d[i, 6] += cur_angle
+
+ return gt_bboxes_3d, pts
+
+
+def object_noise(data_dict, num_try, translation_std, rot_range):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ num_try: int, 100
+ translation_std: shape=[3, ]
+ rot_range: shape=[2, ]
+ return: data_dict
+ '''
+ pts, gt_bboxes_3d = data_dict['pts'], data_dict['gt_bboxes_3d']
+ n_bbox = len(gt_bboxes_3d)
+
+ # 1. generate rotation vectors and rotation matrices
+ trans_vec = np.random.normal(scale=translation_std, size=(n_bbox, num_try, 3)).astype(np.float32)
+ rot_angle = np.random.uniform(rot_range[0], rot_range[1], size=(n_bbox, num_try)).astype(np.float32)
+ rot_cos, rot_sin = np.cos(rot_angle), np.sin(rot_angle)
+ # in fact, - rot_angle
+ rot_mat = np.array([[rot_cos, rot_sin],
+ [-rot_sin, rot_cos]]) # (2, 2, n_bbox, num_try)
+ rot_mat = np.transpose(rot_mat, (2, 3, 1, 0)) # (n_bbox, num_try, 2, 2)
+
+ # 2. generate noise for each bbox and the points inside the bbox.
+ bev_corners = bbox3d2bevcorners(gt_bboxes_3d) # (n_bbox, 4, 2) # for collision test
+ masks = remove_pts_in_bboxes(pts, gt_bboxes_3d, rm=False) # identify which point should be added noise
+ gt_bboxes_3d, pts = object_noise_core(pts=pts,
+ gt_bboxes_3d=gt_bboxes_3d,
+ bev_corners=bev_corners,
+ trans_vec=trans_vec,
+ rot_angle=rot_angle,
+ rot_mat=rot_mat,
+ masks=masks)
+ data_dict.update({'gt_bboxes_3d': gt_bboxes_3d})
+ data_dict.update({'pts': pts})
+
+ return data_dict
+
+
+def random_flip(data_dict, random_flip_ratio):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ random_flip_ratio: float, 0-1
+ return: data_dict
+ '''
+ random_flip_state = np.random.choice([True, False], p=[random_flip_ratio, 1-random_flip_ratio])
+ if random_flip_state:
+ pts, gt_bboxes_3d = data_dict['pts'], data_dict['gt_bboxes_3d']
+ pts[:, 1] = -pts[:, 1]
+ gt_bboxes_3d[:, 1] = -gt_bboxes_3d[:, 1]
+ gt_bboxes_3d[:, 6] = -gt_bboxes_3d[:, 6] + np.pi
+ data_dict.update({'gt_bboxes_3d': gt_bboxes_3d})
+ data_dict.update({'pts': pts})
+ return data_dict
+
+
+def global_rot_scale_trans(data_dict, rot_range, scale_ratio_range, translation_std):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ rot_range: [a, b]
+ scale_ratio_range: [c, d]
+ translation_std: [e, f, g]
+ return: data_dict
+ '''
+ pts, gt_bboxes_3d = data_dict['pts'], data_dict['gt_bboxes_3d']
+
+ # 1. rotation
+ rot_angle = np.random.uniform(rot_range[0], rot_range[1])
+ rot_cos, rot_sin = np.cos(rot_angle), np.sin(rot_angle)
+ # in fact, - rot_angle
+ rot_mat = np.array([[rot_cos, rot_sin],
+ [-rot_sin, rot_cos]]) # (2, 2)
+ # 1.1 bbox rotation
+ gt_bboxes_3d[:, :2] = gt_bboxes_3d[:, :2] @ rot_mat.T
+ gt_bboxes_3d[:, 6] += rot_angle
+ # 1.2 point rotation
+ pts[:, :2] = pts[:, :2] @ rot_mat.T
+
+ # 2. scaling
+ scale_fator = np.random.uniform(scale_ratio_range[0], scale_ratio_range[1])
+ gt_bboxes_3d[:, :6] *= scale_fator
+ pts[:, :3] *= scale_fator
+
+ # 3. translation
+ trans_factor = np.random.normal(scale=translation_std, size=(1, 3))
+ gt_bboxes_3d[:, :3] += trans_factor
+ pts[:, :3] += trans_factor
+ data_dict.update({'gt_bboxes_3d': gt_bboxes_3d})
+ data_dict.update({'pts': pts})
+ return data_dict
+
+
+def point_range_filter(data_dict, point_range):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ point_range: [x1, y1, z1, x2, y2, z2]
+ '''
+ pts = data_dict['pts']
+ flag_x_low = pts[:, 0] > point_range[0]
+ flag_y_low = pts[:, 1] > point_range[1]
+ flag_z_low = pts[:, 2] > point_range[2]
+ flag_x_high = pts[:, 0] < point_range[3]
+ flag_y_high = pts[:, 1] < point_range[4]
+ flag_z_high = pts[:, 2] < point_range[5]
+ keep_mask = flag_x_low & flag_y_low & flag_z_low & flag_x_high & flag_y_high & flag_z_high
+ pts = pts[keep_mask]
+ data_dict.update({'pts': pts})
+ return data_dict
+
+
+def object_range_filter(data_dict, object_range):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ point_range: [x1, y1, z1, x2, y2, z2]
+ '''
+ gt_bboxes_3d, gt_labels = data_dict['gt_bboxes_3d'], data_dict['gt_labels']
+ gt_names, difficulty = data_dict['gt_names'], data_dict['difficulty']
+
+ # bev filter
+ flag_x_low = gt_bboxes_3d[:, 0] > object_range[0]
+ flag_y_low = gt_bboxes_3d[:, 1] > object_range[1]
+ flag_x_high = gt_bboxes_3d[:, 0] < object_range[3]
+ flag_y_high = gt_bboxes_3d[:, 1] < object_range[4]
+ keep_mask = flag_x_low & flag_y_low & flag_x_high & flag_y_high
+
+ gt_bboxes_3d, gt_labels = gt_bboxes_3d[keep_mask], gt_labels[keep_mask]
+ gt_names, difficulty = gt_names[keep_mask], difficulty[keep_mask]
+ gt_bboxes_3d[:, 6] = limit_period(gt_bboxes_3d[:, 6], 0.5, 2 * np.pi)
+ data_dict.update({'gt_bboxes_3d': gt_bboxes_3d})
+ data_dict.update({'gt_labels': gt_labels})
+ data_dict.update({'gt_names': gt_names})
+ data_dict.update({'difficulty': difficulty})
+ return data_dict
+
+
+def points_shuffle(data_dict):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ '''
+ pts = data_dict['pts']
+ indices = np.arange(0, len(pts))
+ np.random.shuffle(indices)
+ pts = pts[indices]
+ data_dict.update({'pts': pts})
+ return data_dict
+
+
+def filter_bboxes_with_labels(data_dict, label=-1):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ label: int
+ '''
+ gt_bboxes_3d, gt_labels = data_dict['gt_bboxes_3d'], data_dict['gt_labels']
+ gt_names, difficulty = data_dict['gt_names'], data_dict['difficulty']
+ idx = gt_labels != label
+ gt_bboxes_3d = gt_bboxes_3d[idx]
+ gt_labels = gt_labels[idx]
+ gt_names = gt_names[idx]
+ difficulty = difficulty[idx]
+ data_dict.update({'gt_bboxes_3d': gt_bboxes_3d})
+ data_dict.update({'gt_labels': gt_labels})
+ data_dict.update({'gt_names': gt_names})
+ data_dict.update({'difficulty': difficulty})
+ return data_dict
+
+
+def data_augment(CLASSES, data_root, data_dict, data_aug_config):
+ '''
+ CLASSES: dict(Pedestrian=0, Cyclist=1, Car=2)
+ data_root: str, data root
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ data_aug_config: dict()
+ return: data_dict
+ '''
+
+ # 1. sample databases and merge into the data
+ db_sampler_config = data_aug_config['db_sampler']
+ data_dict = dbsample(CLASSES,
+ data_root,
+ data_dict,
+ db_sampler=db_sampler_config['db_sampler'],
+ sample_groups=db_sampler_config['sample_groups'])
+ # 2. object noise
+ object_noise_config = data_aug_config['object_noise']
+ data_dict = object_noise(data_dict,
+ num_try=object_noise_config['num_try'],
+ translation_std=object_noise_config['translation_std'],
+ rot_range=object_noise_config['rot_range'])
+
+ # 3. random flip
+ random_flip_ratio = data_aug_config['random_flip_ratio']
+ data_dict = random_flip(data_dict, random_flip_ratio)
+
+ # 4. global rotation, scaling and translation
+ global_rot_scale_trans_config = data_aug_config['global_rot_scale_trans']
+ rot_range = global_rot_scale_trans_config['rot_range']
+ scale_ratio_range = global_rot_scale_trans_config['scale_ratio_range']
+ translation_std = global_rot_scale_trans_config['translation_std']
+ data_dict = global_rot_scale_trans(data_dict, rot_range, scale_ratio_range, translation_std)
+
+ # 5. points range filter
+ point_range = data_aug_config['point_range_filter']
+ data_dict = point_range_filter(data_dict, point_range)
+
+ # 6. object range filter
+ object_range = data_aug_config['object_range_filter']
+ data_dict = object_range_filter(data_dict, object_range)
+
+ # 7. points shuffle
+ data_dict = points_shuffle(data_dict)
+
+ # # 8. filter bboxes with label=-1
+ # data_dict = filter_bboxes_with_labels(data_dict)
+
+ return data_dict
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/dataloader.py b/notebooks/3D-point-pillars/pointpillars/dataset/dataloader.py
new file mode 100644
index 00000000000..2ddbc0da6ee
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/dataloader.py
@@ -0,0 +1,50 @@
+import random
+import numpy as np
+import torch
+from torch.utils.data import DataLoader
+from functools import partial
+
+
+def collate_fn(list_data):
+ batched_pts_list, batched_gt_bboxes_list = [], []
+ batched_labels_list, batched_names_list = [], []
+ batched_difficulty_list = []
+ batched_img_list, batched_calib_list = [], []
+ for data_dict in list_data:
+ pts, gt_bboxes_3d = data_dict['pts'], data_dict['gt_bboxes_3d']
+ gt_labels, gt_names = data_dict['gt_labels'], data_dict['gt_names']
+ difficulty = data_dict['difficulty']
+ image_info, calbi_info = data_dict['image_info'], data_dict['calib_info']
+
+ batched_pts_list.append(torch.from_numpy(pts))
+ batched_gt_bboxes_list.append(torch.from_numpy(gt_bboxes_3d))
+ batched_labels_list.append(torch.from_numpy(gt_labels))
+ batched_names_list.append(gt_names) # List(str)
+ batched_difficulty_list.append(torch.from_numpy(difficulty))
+ batched_img_list.append(image_info)
+ batched_calib_list.append(calbi_info)
+
+ rt_data_dict = dict(
+ batched_pts=batched_pts_list,
+ batched_gt_bboxes=batched_gt_bboxes_list,
+ batched_labels=batched_labels_list,
+ batched_names=batched_names_list,
+ batched_difficulty=batched_difficulty_list,
+ batched_img_info=batched_img_list,
+ batched_calib_info=batched_calib_list
+ )
+
+ return rt_data_dict
+
+
+def get_dataloader(dataset, batch_size, num_workers, shuffle=True, drop_last=False):
+ collate = collate_fn
+ dataloader = DataLoader(
+ dataset=dataset,
+ batch_size=batch_size,
+ shuffle=shuffle,
+ num_workers=num_workers,
+ drop_last=drop_last,
+ collate_fn=collate,
+ )
+ return dataloader
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.bin b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.bin
new file mode 100755
index 00000000000..d68b28f245b
Binary files /dev/null and b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.bin differ
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.png b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.png
new file mode 100755
index 00000000000..e3260bf5603
Binary files /dev/null and b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.png differ
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.txt b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.txt
new file mode 100755
index 00000000000..f8a223dbf17
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/test/000002.txt
@@ -0,0 +1,8 @@
+P0: 7.215377000000e+02 0.000000000000e+00 6.095593000000e+02 0.000000000000e+00 0.000000000000e+00 7.215377000000e+02 1.728540000000e+02 0.000000000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 0.000000000000e+00
+P1: 7.215377000000e+02 0.000000000000e+00 6.095593000000e+02 -3.875744000000e+02 0.000000000000e+00 7.215377000000e+02 1.728540000000e+02 0.000000000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 0.000000000000e+00
+P2: 7.215377000000e+02 0.000000000000e+00 6.095593000000e+02 4.485728000000e+01 0.000000000000e+00 7.215377000000e+02 1.728540000000e+02 2.163791000000e-01 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 2.745884000000e-03
+P3: 7.215377000000e+02 0.000000000000e+00 6.095593000000e+02 -3.395242000000e+02 0.000000000000e+00 7.215377000000e+02 1.728540000000e+02 2.199936000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 2.729905000000e-03
+R0_rect: 9.999239000000e-01 9.837760000000e-03 -7.445048000000e-03 -9.869795000000e-03 9.999421000000e-01 -4.278459000000e-03 7.402527000000e-03 4.351614000000e-03 9.999631000000e-01
+Tr_velo_to_cam: 7.533745000000e-03 -9.999714000000e-01 -6.166020000000e-04 -4.069766000000e-03 1.480249000000e-02 7.280733000000e-04 -9.998902000000e-01 -7.631618000000e-02 9.998621000000e-01 7.523790000000e-03 1.480755000000e-02 -2.717806000000e-01
+Tr_imu_to_velo: 9.999976000000e-01 7.553071000000e-04 -2.035826000000e-03 -8.086759000000e-01 -7.854027000000e-04 9.998898000000e-01 -1.482298000000e-02 3.195559000000e-01 2.024406000000e-03 1.482454000000e-02 9.998881000000e-01 -7.997231000000e-01
+
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.bin b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.bin
new file mode 100755
index 00000000000..03011c96156
Binary files /dev/null and b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.bin differ
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.png b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.png
new file mode 100755
index 00000000000..a4174c41409
Binary files /dev/null and b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.png differ
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.txt b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.txt
new file mode 100755
index 00000000000..7ed0fbf2388
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134.txt
@@ -0,0 +1,8 @@
+P0: 7.070493000000e+02 0.000000000000e+00 6.040814000000e+02 0.000000000000e+00 0.000000000000e+00 7.070493000000e+02 1.805066000000e+02 0.000000000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 0.000000000000e+00
+P1: 7.070493000000e+02 0.000000000000e+00 6.040814000000e+02 -3.797842000000e+02 0.000000000000e+00 7.070493000000e+02 1.805066000000e+02 0.000000000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 0.000000000000e+00
+P2: 7.070493000000e+02 0.000000000000e+00 6.040814000000e+02 4.575831000000e+01 0.000000000000e+00 7.070493000000e+02 1.805066000000e+02 -3.454157000000e-01 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 4.981016000000e-03
+P3: 7.070493000000e+02 0.000000000000e+00 6.040814000000e+02 -3.341081000000e+02 0.000000000000e+00 7.070493000000e+02 1.805066000000e+02 2.330660000000e+00 0.000000000000e+00 0.000000000000e+00 1.000000000000e+00 3.201153000000e-03
+R0_rect: 9.999128000000e-01 1.009263000000e-02 -8.511932000000e-03 -1.012729000000e-02 9.999406000000e-01 -4.037671000000e-03 8.470675000000e-03 4.123522000000e-03 9.999556000000e-01
+Tr_velo_to_cam: 6.927964000000e-03 -9.999722000000e-01 -2.757829000000e-03 -2.457729000000e-02 -1.162982000000e-03 2.749836000000e-03 -9.999955000000e-01 -6.127237000000e-02 9.999753000000e-01 6.931141000000e-03 -1.143899000000e-03 -3.321029000000e-01
+Tr_imu_to_velo: 9.999976000000e-01 7.553071000000e-04 -2.035826000000e-03 -8.086759000000e-01 -7.854027000000e-04 9.998898000000e-01 -1.482298000000e-02 3.195559000000e-01 2.024406000000e-03 1.482454000000e-02 9.998881000000e-01 -7.997231000000e-01
+
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134_gt.txt b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134_gt.txt
new file mode 100755
index 00000000000..a3c366a0974
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/demo_data/val/000134_gt.txt
@@ -0,0 +1,17 @@
+Car 0.00 0 -1.33 333.28 177.65 489.60 277.55 1.50 1.78 3.69 -3.29 1.46 12.65 -1.57
+Cyclist 0.00 1 -0.32 1084.56 129.65 1195.82 213.78 1.74 0.60 1.79 11.42 0.70 15.18 0.32
+Cyclist 0.00 1 -0.50 993.86 137.83 1070.27 203.41 1.86 0.63 1.82 12.42 0.65 20.63 0.04
+Pedestrian 0.00 0 0.14 562.59 158.20 594.85 225.88 1.83 0.69 1.03 -0.77 1.23 19.57 0.10
+Cyclist 0.00 1 -0.55 790.12 154.43 834.52 194.72 1.72 0.60 1.79 9.01 0.60 30.76 -0.27
+Pedestrian 0.00 2 0.26 402.59 157.37 427.24 234.07 1.80 0.61 1.04 -4.61 1.26 17.02 0.00
+Cyclist 0.00 0 -1.41 858.79 151.31 887.58 197.13 1.72 0.78 1.71 10.44 0.62 27.53 -1.05
+Pedestrian 0.00 1 0.65 196.36 177.31 229.19 234.95 1.72 0.55 0.93 -11.93 1.63 21.48 0.15
+Pedestrian 0.00 0 0.64 189.12 181.00 219.25 236.74 1.62 0.48 0.96 -11.93 1.64 20.91 0.13
+Cyclist 0.00 1 -0.19 283.29 168.34 364.92 241.44 1.70 0.64 1.74 -6.87 1.41 17.25 -0.57
+Pedestrian 0.00 0 -2.72 241.89 176.88 270.18 234.71 1.60 0.54 0.84 -9.82 1.51 20.03 3.12
+Pedestrian 0.00 0 -3.01 210.60 172.77 242.54 244.30 1.80 0.54 1.03 -9.70 1.61 18.32 2.80
+Pedestrian 0.00 1 -2.78 334.47 162.73 354.71 234.29 1.95 0.56 0.82 -7.16 1.47 19.63 -3.13
+Car 0.43 1 -0.71 1137.36 137.54 1223.00 177.88 1.55 1.81 4.39 24.40 -0.13 28.60 -0.01
+Car 0.00 1 -0.58 1028.25 151.61 1157.03 185.90 1.28 1.70 3.95 19.45 0.18 28.33 0.02
+DontCare -1 -1 -10 623.97 162.02 652.39 174.14 -1 -1 -1 -1000 -1000 -1000 -10
+DontCare -1 -1 -10 473.26 166.51 498.98 191.20 -1 -1 -1 -1000 -1000 -1000 -10
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/kitti.py b/notebooks/3D-point-pillars/pointpillars/dataset/kitti.py
new file mode 100644
index 00000000000..371e63b63d3
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/kitti.py
@@ -0,0 +1,148 @@
+import numpy as np
+import os
+import torch
+from torch.utils.data import Dataset
+
+import sys
+BASE = os.path.dirname(os.path.abspath(__file__))
+sys.path.append(os.path.dirname(BASE))
+
+from pointpillars.utils import read_pickle, read_points, bbox_camera2lidar
+from pointpillars.dataset import point_range_filter, data_augment
+
+
+class BaseSampler():
+ def __init__(self, sampled_list, shuffle=True):
+ self.total_num = len(sampled_list)
+ self.sampled_list = np.array(sampled_list)
+ self.indices = np.arange(self.total_num)
+ if shuffle:
+ np.random.shuffle(self.indices)
+ self.shuffle = shuffle
+ self.idx = 0
+
+ def sample(self, num):
+ if self.idx + num < self.total_num:
+ ret = self.sampled_list[self.indices[self.idx:self.idx+num]]
+ self.idx += num
+ else:
+ ret = self.sampled_list[self.indices[self.idx:]]
+ self.idx = 0
+ if self.shuffle:
+ np.random.shuffle(self.indices)
+ return ret
+
+
+class Kitti(Dataset):
+
+ CLASSES = {
+ 'Pedestrian': 0,
+ 'Cyclist': 1,
+ 'Car': 2
+ }
+
+ def __init__(self, data_root, split, pts_prefix='velodyne_reduced', max_samples=None):
+ assert split in ['train', 'val', 'trainval', 'test']
+ self.data_root = data_root
+ self.split = split
+ self.pts_prefix = pts_prefix
+ self.data_infos = read_pickle(os.path.join(data_root, f'kitti_infos_{split}.pkl'))
+ self.sorted_ids = list(self.data_infos.keys())
+ if max_samples is not None and max_samples > 0:
+ max_samples = min(max_samples, len(self.sorted_ids))
+ self.sorted_ids = self.sorted_ids[:max_samples]
+ self.data_infos = {k: self.data_infos[k] for k in self.sorted_ids}
+ db_infos = read_pickle(os.path.join(data_root, 'kitti_dbinfos_train.pkl'))
+ db_infos = self.filter_db(db_infos)
+
+ db_sampler = {}
+ for cat_name in self.CLASSES:
+ db_sampler[cat_name] = BaseSampler(db_infos[cat_name], shuffle=True)
+ self.data_aug_config=dict(
+ db_sampler=dict(
+ db_sampler=db_sampler,
+ sample_groups=dict(Car=15, Pedestrian=10, Cyclist=10)
+ ),
+ object_noise=dict(
+ num_try=100,
+ translation_std=[0.25, 0.25, 0.25],
+ rot_range=[-0.15707963267, 0.15707963267]
+ ),
+ random_flip_ratio=0.5,
+ global_rot_scale_trans=dict(
+ rot_range=[-0.78539816, 0.78539816],
+ scale_ratio_range=[0.95, 1.05],
+ translation_std=[0, 0, 0]
+ ),
+ point_range_filter=[0, -39.68, -3, 69.12, 39.68, 1],
+ object_range_filter=[0, -39.68, -3, 69.12, 39.68, 1]
+ )
+
+ def remove_dont_care(self, annos_info):
+ keep_ids = [i for i, name in enumerate(annos_info['name']) if name != 'DontCare']
+ for k, v in annos_info.items():
+ annos_info[k] = v[keep_ids]
+ return annos_info
+
+ def filter_db(self, db_infos):
+ # 1. filter_by_difficulty
+ for k, v in db_infos.items():
+ db_infos[k] = [item for item in v if item['difficulty'] != -1]
+
+ # 2. filter_by_min_points, dict(Car=5, Pedestrian=10, Cyclist=10)
+ filter_thrs = dict(Car=5, Pedestrian=10, Cyclist=10)
+ for cat in self.CLASSES:
+ filter_thr = filter_thrs[cat]
+ db_infos[cat] = [item for item in db_infos[cat] if item['num_points_in_gt'] >= filter_thr]
+
+ return db_infos
+
+ def __getitem__(self, index):
+ data_info = self.data_infos[self.sorted_ids[index]]
+ image_info, calib_info, annos_info = \
+ data_info['image'], data_info['calib'], data_info['annos']
+
+ # point cloud input
+ velodyne_path = data_info['velodyne_path'].replace('velodyne', self.pts_prefix)
+ pts_path = os.path.join(self.data_root, velodyne_path)
+ pts = read_points(pts_path)
+
+ # calib input: for bbox coordinates transformation between Camera and Lidar.
+ # because
+ tr_velo_to_cam = calib_info['Tr_velo_to_cam'].astype(np.float32)
+ r0_rect = calib_info['R0_rect'].astype(np.float32)
+
+ # annotations input
+ annos_info = self.remove_dont_care(annos_info)
+ annos_name = annos_info['name']
+ annos_location = annos_info['location']
+ annos_dimension = annos_info['dimensions']
+ rotation_y = annos_info['rotation_y']
+ gt_bboxes = np.concatenate([annos_location, annos_dimension, rotation_y[:, None]], axis=1).astype(np.float32)
+ gt_bboxes_3d = bbox_camera2lidar(gt_bboxes, tr_velo_to_cam, r0_rect)
+ gt_labels = [self.CLASSES.get(name, -1) for name in annos_name]
+ data_dict = {
+ 'pts': pts,
+ 'gt_bboxes_3d': gt_bboxes_3d,
+ 'gt_labels': np.array(gt_labels),
+ 'gt_names': annos_name,
+ 'difficulty': annos_info['difficulty'],
+ 'image_info': image_info,
+ 'calib_info': calib_info
+ }
+ if self.split in ['train', 'trainval']:
+ data_dict = data_augment(self.CLASSES, self.data_root, data_dict, self.data_aug_config)
+ else:
+ data_dict = point_range_filter(data_dict, point_range=self.data_aug_config['point_range_filter'])
+
+ return data_dict
+
+ def __len__(self):
+ return len(self.data_infos)
+
+
+if __name__ == '__main__':
+
+ kitti_data = Kitti(data_root='/mnt/ssd1/lifa_rdata/det/kitti',
+ split='train')
+ kitti_data.__getitem__(9)
diff --git a/notebooks/3D-point-pillars/pointpillars/dataset/kitti_open3d/utils.py b/notebooks/3D-point-pillars/pointpillars/dataset/kitti_open3d/utils.py
new file mode 100644
index 00000000000..af17e7c14f6
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/dataset/kitti_open3d/utils.py
@@ -0,0 +1,169 @@
+import os
+import numpy as np
+import open3d as o3d
+
+def read_kitti_pcd(pcd_path):
+ """
+ Read a binary PCD written as FIELDS x y z intensity and return Nx4 float32 array.
+
+ Strategy:
+ 1. Try Open3D tensor API (o3d.t.io.read_point_cloud) — preserves attributes including 'intensity'.
+ 2. If intensity is not available from Open3D, fall back to the robust parser
+ (pointpillars.dataset.kitti_open3d.utils.read_pcd_xyzi) which reads the binary payload directly.
+
+ Returns:
+ Nx4 numpy float32 array: columns x, y, z, intensity (intensity filled with 0.0 if absent).
+ """
+
+ # 1) Try Open3D tensor API (o3d.t.io.read_point_cloud)
+ try:
+ pcd_t = o3d.t.io.read_point_cloud(pcd_path) # returns o3d.t.geometry.PointCloud-like
+
+ # positions
+ pos = pcd_t.point.positions.numpy().astype(np.float32)
+
+ # intensity
+ if "intensity" in pcd_t.point:
+ inten = pcd_t.point["intensity"].numpy().astype(np.float32).reshape(-1, 1)
+ else:
+ # no intensity attribute available in tensor API -> pad zeros
+ inten = np.zeros((pos.shape[0], 1), dtype=np.float32)
+
+ return np.concatenate([pos, inten], axis=1)
+ except Exception:
+ # Something unexpected in tensor read; fall through to legacy
+ print(f"Warning: Open3D tensor read failed for {pcd_path}, falling back to custom reader.")
+
+ # 2) Guaranteed fallback: parse the PCD file directly to guarantee [x,y,z,intensity]
+ return read_pcd_xyzi(pcd_path)
+
+
+def read_pcd_xyzi(pcd_path):
+ """Read a binary PCD file with FIELDS x y z intensity and return Nx4 float32 array.
+
+ This is the inverse of convert_bin_to_pcd() and returns exactly the same
+ data structure as reading a KITTI .bin file with np.fromfile().reshape(-1,4).
+ """
+ with open(pcd_path, 'rb') as f:
+ # Read header lines until DATA
+ n_points = None
+ while True:
+ line = f.readline().decode('ascii').strip()
+ if line.startswith('POINTS'):
+ n_points = int(line.split()[1])
+ if line.startswith('DATA'):
+ break
+
+ if n_points is None:
+ raise ValueError(f"Could not find POINTS in PCD header: {pcd_path}")
+
+ # Read binary payload
+ binary_data = f.read()
+
+ pts = np.frombuffer(binary_data, dtype=np.float32).reshape(n_points, 4).copy()
+ return pts
+
+
+def convert_bin_to_pcd(bin_path, pcd_path):
+ """Convert KITTI .bin (x,y,z,intensity float32) to binary PCD preserving ALL fields.
+
+ Writes a proper PCD with FIELDS x y z intensity so intensity is preserved
+ as a numeric scalar field (not just colors). Compatible with PCL and other
+ PCD readers that support scalar fields.
+ """
+ pts = np.fromfile(bin_path, dtype=np.float32).reshape(-1, 4)
+ N = pts.shape[0]
+
+ # Write binary PCD with header describing all 4 fields
+ header = (
+ "# .PCD v0.7 - Point Cloud Data file format\n"
+ "VERSION 0.7\n"
+ "FIELDS x y z intensity\n"
+ "SIZE 4 4 4 4\n"
+ "TYPE F F F F\n"
+ "COUNT 1 1 1 1\n"
+ f"WIDTH {N}\n"
+ "HEIGHT 1\n"
+ "VIEWPOINT 0 0 0 1 0 0 0\n"
+ f"POINTS {N}\n"
+ "DATA binary\n"
+ )
+
+ with open(pcd_path, 'wb') as f:
+ f.write(header.encode('ascii'))
+ # Write raw binary float32 data (little-endian, C-contiguous)
+ f.write(pts.astype(np.float32).tobytes(order='C'))
+
+
+def compare_bin_pcd_pts(pts_bin, pts_pcd, rtol=1e-5, atol=1e-8, verbose=True):
+ """Compare .bin and .pcd files for data equality.
+
+ Returns True if shapes match and all values are equal within tolerance.
+ Prints summary if verbose=True.
+ """
+ if pts_bin.shape != pts_pcd.shape:
+ if verbose:
+ print(f"✗ Shape mismatch: bin={pts_bin.shape}, pcd={pts_pcd.shape}")
+ return False
+
+ if np.allclose(pts_bin, pts_pcd, rtol=rtol, atol=atol):
+ if verbose:
+ print(f"✓ Data matches: {pts_bin.shape[0]} points, all values within tolerance")
+ print(f" Intensity range: [{pts_bin[:,3].min():.4f}, {pts_bin[:,3].max():.4f}]")
+ return True
+
+ # Report differences
+ diff = np.abs(pts_bin - pts_pcd)
+ n_diff = np.sum(~np.isclose(pts_bin, pts_pcd, rtol=rtol, atol=atol))
+ if verbose:
+ print(f"✗ Data mismatch: {n_diff} values differ, max diff={diff.max():.6g}")
+ return False
+
+
+def compare_bin_pcd_file(bin_path, pcd_path, rtol=1e-5, atol=1e-8, verbose=True):
+ """Compare .bin and .pcd files for data equality.
+
+ Returns True if shapes match and all values are equal within tolerance.
+ Prints summary if verbose=True.
+ """
+ # Read .bin
+ pts_bin = np.fromfile(bin_path, dtype=np.float32).reshape(-1, 4)
+
+ # Read .pcd
+ pts_pcd = read_kitti_pcd(pcd_path)
+
+ return compare_bin_pcd_pts(pts_bin, pts_pcd, rtol, atol, verbose)
+
+
+if __name__ == "__main__":
+ # Simple test: convert a .bin to .pcd and back, then compare
+ import tempfile
+ import sys
+
+ # Default demo .bin in the repo (used when no path is provided)
+ default_bin = os.path.abspath(os.path.join(os.path.dirname(__file__), '..', 'demo_data', 'test', '000002.bin'))
+
+ if len(sys.argv) == 1:
+ bin_path = default_bin
+ print(f"No input provided, using default demo file: {bin_path}")
+ elif len(sys.argv) == 2:
+ bin_path = sys.argv[1]
+ else:
+ print(f"Usage: {sys.argv[0]} [path_to_bin_file]", file=sys.stderr)
+ sys.exit(1)
+
+ if not os.path.isfile(bin_path):
+ print(f"File not found: {bin_path}", file=sys.stderr)
+ sys.exit(1)
+
+ with tempfile.TemporaryDirectory() as tmpdir:
+ pcd_path = os.path.join(tmpdir, "temp.pcd")
+ convert_bin_to_pcd(bin_path, pcd_path)
+ print(f"Converted {bin_path} -> {pcd_path}")
+
+ match = compare_bin_pcd_file(bin_path, pcd_path, verbose=True)
+ if match:
+ print("✓ Conversion verified: .bin and .pcd data match")
+ else:
+ print("✗ Conversion verification failed: data mismatch", file=sys.stderr)
+ sys.exit(1)
diff --git a/notebooks/3D-point-pillars/pointpillars/loss/__init__.py b/notebooks/3D-point-pillars/pointpillars/loss/__init__.py
new file mode 100644
index 00000000000..fcd1262a088
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/loss/__init__.py
@@ -0,0 +1 @@
+from .loss import Loss
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/loss/loss.py b/notebooks/3D-point-pillars/pointpillars/loss/loss.py
new file mode 100644
index 00000000000..016e0460aac
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/loss/loss.py
@@ -0,0 +1,66 @@
+import pdb
+import torch
+import torch.nn as nn
+import torch.nn.functional as F
+
+
+class Loss(nn.Module):
+ def __init__(self, alpha=0.25, gamma=2.0, beta=1/9, cls_w=1.0, reg_w=2.0, dir_w=0.2):
+ super().__init__()
+ self.alpha = 0.25
+ self.gamma = 2.0
+ self.cls_w = cls_w
+ self.reg_w = reg_w
+ self.dir_w = dir_w
+ self.smooth_l1_loss = nn.SmoothL1Loss(reduction='none',
+ beta=beta)
+ self.dir_cls = nn.CrossEntropyLoss()
+
+ def forward(self,
+ bbox_cls_pred,
+ bbox_pred,
+ bbox_dir_cls_pred,
+ batched_labels,
+ num_cls_pos,
+ batched_bbox_reg,
+ batched_dir_labels):
+ '''
+ bbox_cls_pred: (n, 3)
+ bbox_pred: (n, 7)
+ bbox_dir_cls_pred: (n, 2)
+ batched_labels: (n, )
+ num_cls_pos: int
+ batched_bbox_reg: (n, 7)
+ batched_dir_labels: (n, )
+ return: loss, float.
+ '''
+ # 1. bbox cls loss
+ # focal loss: FL = - \alpha_t (1 - p_t)^\gamma * log(p_t)
+ # y == 1 -> p_t = p
+ # y == 0 -> p_t = 1 - p
+ nclasses = bbox_cls_pred.size(1)
+ batched_labels = F.one_hot(batched_labels, nclasses + 1)[:, :nclasses].float() # (n, 3)
+
+ bbox_cls_pred_sigmoid = torch.sigmoid(bbox_cls_pred)
+ weights = self.alpha * (1 - bbox_cls_pred_sigmoid).pow(self.gamma) * batched_labels + \
+ (1 - self.alpha) * bbox_cls_pred_sigmoid.pow(self.gamma) * (1 - batched_labels) # (n, 3)
+ cls_loss = F.binary_cross_entropy(bbox_cls_pred_sigmoid, batched_labels, reduction='none')
+ cls_loss = cls_loss * weights
+ cls_loss = cls_loss.sum() / num_cls_pos
+
+ # 2. regression loss
+ reg_loss = self.smooth_l1_loss(bbox_pred, batched_bbox_reg)
+ reg_loss = reg_loss.sum() / reg_loss.size(0)
+
+ # 3. direction cls loss
+ dir_cls_loss = self.dir_cls(bbox_dir_cls_pred, batched_dir_labels)
+
+ # 4. total loss
+ total_loss = self.cls_w * cls_loss + self.reg_w * reg_loss + self.dir_w * dir_cls_loss
+
+ loss_dict={'cls_loss': cls_loss,
+ 'reg_loss': reg_loss,
+ 'dir_cls_loss': dir_cls_loss,
+ 'total_loss': total_loss}
+ return loss_dict
+
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/model/__init__.py b/notebooks/3D-point-pillars/pointpillars/model/__init__.py
new file mode 100644
index 00000000000..d113378f5cd
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/model/__init__.py
@@ -0,0 +1,2 @@
+from .anchors import Anchors, anchors2bboxes, bboxes2deltas
+from .pointpillars import PointPillars, PillarLayer, PillarEncoder
diff --git a/notebooks/3D-point-pillars/pointpillars/model/anchors.py b/notebooks/3D-point-pillars/pointpillars/model/anchors.py
new file mode 100644
index 00000000000..20a07c91765
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/model/anchors.py
@@ -0,0 +1,231 @@
+import pdb
+import numpy as np
+import torch
+from pointpillars.utils import limit_period, iou2d_nearest
+
+
+class Anchors():
+ def __init__(self, ranges, sizes, rotations):
+ assert len(ranges) == len(sizes)
+ self.ranges = ranges
+ self.sizes = sizes
+ self.rotations = rotations
+
+ def get_anchors(self, feature_map_size, anchor_range, anchor_size, rotations):
+ '''
+ feature_map_size: (y_l, x_l)
+ anchor_range: [x1, y1, z1, x2, y2, z2]
+ anchor_size: [w, l, h]
+ rotations: [0, 1.57]
+ return: shape=(y_l, x_l, 2, 7)
+ '''
+ device = feature_map_size.device
+ x_centers = torch.linspace(anchor_range[0], anchor_range[3], feature_map_size[1] + 1, device=device)
+ y_centers = torch.linspace(anchor_range[1], anchor_range[4], feature_map_size[0] + 1, device=device)
+ z_centers = torch.linspace(anchor_range[2], anchor_range[5], 1 + 1, device=device)
+
+ x_shift = (x_centers[1] - x_centers[0]) / 2
+ y_shift = (y_centers[1] - y_centers[0]) / 2
+ z_shift = (z_centers[1] - z_centers[0]) / 2
+ x_centers = x_centers[:feature_map_size[1]] + x_shift # (feature_map_size[1], )
+ y_centers = y_centers[:feature_map_size[0]] + y_shift # (feature_map_size[0], )
+ z_centers = z_centers[:1] + z_shift # (1, )
+
+ # [feature_map_size[1], feature_map_size[0], 1, 2] * 4
+ meshgrids = torch.meshgrid(x_centers, y_centers, z_centers, rotations)
+ meshgrids = list(meshgrids)
+ for i in range(len(meshgrids)):
+ meshgrids[i] = meshgrids[i][..., None] # [feature_map_size[1], feature_map_size[0], 1, 2, 1]
+
+ anchor_size = anchor_size[None, None, None, None, :]
+ repeat_shape = [feature_map_size[1], feature_map_size[0], 1, len(rotations), 1]
+ anchor_size = anchor_size.repeat(repeat_shape) # [feature_map_size[1], feature_map_size[0], 1, 2, 3]
+ meshgrids.insert(3, anchor_size)
+ anchors = torch.cat(meshgrids, dim=-1).permute(2, 1, 0, 3, 4).contiguous() # [1, feature_map_size[0], feature_map_size[1], 2, 7]
+ return anchors.squeeze(0)
+
+
+ def get_multi_anchors(self, feature_map_size):
+ '''
+ feature_map_size: (y_l, x_l)
+ ranges: [[x1, y1, z1, x2, y2, z2], [x1, y1, z1, x2, y2, z2], [x1, y1, z1, x2, y2, z2]]
+ sizes: [[w, l, h], [w, l, h], [w, l, h]]
+ rotations: [0, 1.57]
+ return: shape=(y_l, x_l, 3, 2, 7)
+ '''
+ device = feature_map_size.device
+ ranges = torch.tensor(self.ranges, device=device)
+ sizes = torch.tensor(self.sizes, device=device)
+ rotations = torch.tensor(self.rotations, device=device)
+ multi_anchors = []
+ for i in range(len(ranges)):
+ anchors = self.get_anchors(feature_map_size=feature_map_size,
+ anchor_range=ranges[i],
+ anchor_size=sizes[i],
+ rotations=rotations)
+ multi_anchors.append(anchors[:, :, None, :, :])
+ multi_anchors = torch.cat(multi_anchors, dim=2)
+
+ return multi_anchors
+
+
+def anchors2bboxes(anchors, deltas):
+ '''
+ anchors: (M, 7), (x, y, z, w, l, h, theta)
+ deltas: (M, 7)
+ return: (M, 7)
+ '''
+ da = torch.sqrt(anchors[:, 3] ** 2 + anchors[:, 4] ** 2)
+ x = deltas[:, 0] * da + anchors[:, 0]
+ y = deltas[:, 1] * da + anchors[:, 1]
+ z = deltas[:, 2] * anchors[:, 5] + anchors[:, 2] + anchors[:, 5] / 2
+
+ w = anchors[:, 3] * torch.exp(deltas[:, 3])
+ l = anchors[:, 4] * torch.exp(deltas[:, 4])
+ h = anchors[:, 5] * torch.exp(deltas[:, 5])
+
+ z = z - h / 2
+
+ theta = anchors[:, 6] + deltas[:, 6]
+
+ bboxes = torch.stack([x, y, z, w, l, h, theta], dim=1)
+ return bboxes
+
+
+def bboxes2deltas(bboxes, anchors):
+ '''
+ bboxes: (M, 7), (x, y, z, w, l, h, theta)
+ anchors: (M, 7)
+ return: (M, 7)
+ '''
+ da = torch.sqrt(anchors[:, 3] ** 2 + anchors[:, 4] ** 2)
+
+ dx = (bboxes[:, 0] - anchors[:, 0]) / da
+ dy = (bboxes[:, 1] - anchors[:, 1]) / da
+
+ zb = bboxes[:, 2] + bboxes[:, 5] / 2 # bottom center
+ za = anchors[:, 2] + anchors[:, 5] / 2 # bottom center
+ dz = (zb - za) / anchors[:, 5] # bottom center
+
+ dw = torch.log(bboxes[:, 3] / anchors[:, 3])
+ dl = torch.log(bboxes[:, 4] / anchors[:, 4])
+ dh = torch.log(bboxes[:, 5] / anchors[:, 5])
+ dtheta = bboxes[:, 6] - anchors[:, 6]
+
+ deltas = torch.stack([dx, dy, dz, dw, dl, dh, dtheta], dim=1)
+ return deltas
+
+
+def anchor_target(batched_anchors, batched_gt_bboxes, batched_gt_labels, assigners, nclasses):
+ '''
+ batched_anchors: [(y_l, x_l, 3, 2, 7), (y_l, x_l, 3, 2, 7), ... ]
+ batched_gt_bboxes: [(n1, 7), (n2, 7), ...]
+ batched_gt_labels: [(n1, ), (n2, ), ...]
+ return:
+ dict = {batched_anchors_labels: (bs, n_anchors),
+ batched_labels_weights: (bs, n_anchors),
+ batched_anchors_reg: (bs, n_anchors, 7),
+ batched_reg_weights: (bs, n_anchors),
+ batched_anchors_dir: (bs, n_anchors),
+ batched_dir_weights: (bs, n_anchors)}
+ '''
+ assert len(batched_anchors) == len(batched_gt_bboxes) == len(batched_gt_labels)
+ batch_size = len(batched_anchors)
+ n_assigners = len(assigners)
+ batched_labels, batched_label_weights = [], []
+ batched_bbox_reg, batched_bbox_reg_weights = [], []
+ batched_dir_labels, batched_dir_labels_weights = [], []
+ for i in range(batch_size):
+ anchors = batched_anchors[i]
+ gt_bboxes, gt_labels = batched_gt_bboxes[i], batched_gt_labels[i]
+ # what we want to get next ?
+ # 1. identify positive anchors and negative anchors -> cls
+ # 2. identify the regresstion values -> reg
+ # 3. indentify the direction -> dir_cls
+ multi_labels, multi_label_weights = [], []
+ multi_bbox_reg, multi_bbox_reg_weights = [], []
+ multi_dir_labels, multi_dir_labels_weights = [], []
+ d1, d2, d3, d4, d5 = anchors.size()
+ for j in range(n_assigners): # multi anchors
+ assigner = assigners[j]
+ pos_iou_thr, neg_iou_thr, min_iou_thr = \
+ assigner['pos_iou_thr'], assigner['neg_iou_thr'], assigner['min_iou_thr']
+ cur_anchors = anchors[:, :, j, :, :].reshape(-1, 7)
+ overlaps = iou2d_nearest(gt_bboxes, cur_anchors)
+ max_overlaps, max_overlaps_idx = torch.max(overlaps, dim=0)
+ gt_max_overlaps, _ = torch.max(overlaps, dim=1)
+
+ assigned_gt_inds = -torch.ones_like(cur_anchors[:, 0], dtype=torch.long)
+ # a. negative anchors
+ assigned_gt_inds[max_overlaps < neg_iou_thr] = 0
+
+ # b. positive anchors
+ # rule 1
+ assigned_gt_inds[max_overlaps >= pos_iou_thr] = max_overlaps_idx[max_overlaps >= pos_iou_thr] + 1
+
+ # rule 2
+ # support one bbox to multi anchors, only if the anchors are with the highest iou.
+ # rule2 may modify the labels generated by rule 1
+ for i in range(len(gt_bboxes)):
+ if gt_max_overlaps[i] >= min_iou_thr:
+ assigned_gt_inds[overlaps[i] == gt_max_overlaps[i]] = i + 1
+
+ pos_flag = assigned_gt_inds > 0
+ neg_flag = assigned_gt_inds == 0
+ # 1. anchor labels
+ assigned_gt_labels = torch.zeros_like(cur_anchors[:, 0], dtype=torch.long) + nclasses # -1 is not optimal, for some bboxes are with labels -1
+ assigned_gt_labels[pos_flag] = gt_labels[assigned_gt_inds[pos_flag] - 1].long()
+ assigned_gt_labels_weights = torch.zeros_like(cur_anchors[:, 0])
+ assigned_gt_labels_weights[pos_flag] = 1
+ assigned_gt_labels_weights[neg_flag] = 1
+
+ # 2. anchor regression
+ assigned_gt_reg_weights = torch.zeros_like(cur_anchors[:, 0])
+ assigned_gt_reg_weights[pos_flag] = 1
+
+ assigned_gt_reg = torch.zeros_like(cur_anchors)
+ positive_anchors = cur_anchors[pos_flag]
+ corr_gt_bboxes = gt_bboxes[assigned_gt_inds[pos_flag] - 1]
+ assigned_gt_reg[pos_flag] = bboxes2deltas(corr_gt_bboxes, positive_anchors)
+
+ # 3. anchor direction
+ assigned_gt_dir_weights = torch.zeros_like(cur_anchors[:, 0])
+ assigned_gt_dir_weights[pos_flag] = 1
+
+ assigned_gt_dir = torch.zeros_like(cur_anchors[:, 0], dtype=torch.long)
+ dir_cls_targets = limit_period(corr_gt_bboxes[:, 6].cpu(), 0, 2 * np.pi).to(corr_gt_bboxes)
+ dir_cls_targets = torch.floor(dir_cls_targets / np.pi).long()
+ assigned_gt_dir[pos_flag] = torch.clamp(dir_cls_targets, min=0, max=1)
+
+ multi_labels.append(assigned_gt_labels.reshape(d1, d2, 1, d4))
+ multi_label_weights.append(assigned_gt_labels_weights.reshape(d1, d2, 1, d4))
+ multi_bbox_reg.append(assigned_gt_reg.reshape(d1, d2, 1, d4, -1))
+ multi_bbox_reg_weights.append(assigned_gt_reg_weights.reshape(d1, d2, 1, d4))
+ multi_dir_labels.append(assigned_gt_dir.reshape(d1, d2, 1, d4))
+ multi_dir_labels_weights.append(assigned_gt_dir_weights.reshape(d1, d2, 1, d4))
+
+ multi_labels = torch.cat(multi_labels, dim=-2).reshape(-1)
+ multi_label_weights = torch.cat(multi_label_weights, dim=-2).reshape(-1)
+ multi_bbox_reg = torch.cat(multi_bbox_reg, dim=-3).reshape(-1, d5)
+ multi_bbox_reg_weights = torch.cat(multi_bbox_reg_weights, dim=-2).reshape(-1)
+ multi_dir_labels = torch.cat(multi_dir_labels, dim=-2).reshape(-1)
+ multi_dir_labels_weights = torch.cat(multi_dir_labels_weights, dim=-2).reshape(-1)
+
+ batched_labels.append(multi_labels)
+ batched_label_weights.append(multi_label_weights)
+ batched_bbox_reg.append(multi_bbox_reg)
+ batched_bbox_reg_weights.append(multi_bbox_reg_weights)
+ batched_dir_labels.append(multi_dir_labels)
+ batched_dir_labels_weights.append(multi_dir_labels_weights)
+
+ rt_dict = dict(
+ batched_labels=torch.stack(batched_labels, 0), # (bs, y_l * x_l * 3 * 2)
+ batched_label_weights=torch.stack(batched_label_weights, 0), # (bs, y_l * x_l * 3 * 2)
+ batched_bbox_reg=torch.stack(batched_bbox_reg, 0), # (bs, y_l * x_l * 3 * 2, 7)
+ batched_bbox_reg_weights=torch.stack(batched_bbox_reg_weights, 0), # (bs, y_l * x_l * 3 * 2)
+ batched_dir_labels=torch.stack(batched_dir_labels, 0), # (bs, y_l * x_l * 3 * 2)
+ batched_dir_labels_weights=torch.stack(batched_dir_labels_weights, 0) # (bs, y_l * x_l * 3 * 2)
+ )
+
+ return rt_dict
+
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/model/pointpillars.py b/notebooks/3D-point-pillars/pointpillars/model/pointpillars.py
new file mode 100644
index 00000000000..a50ee94f7d8
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/model/pointpillars.py
@@ -0,0 +1,427 @@
+import numpy as np
+import pdb
+import torch
+import torch.nn as nn
+import torch.nn.functional as F
+from pointpillars.model.anchors import Anchors, anchor_target, anchors2bboxes
+from pointpillars.ops import Voxelization, nms_cuda
+from pointpillars.utils import limit_period
+
+
+class PillarLayer(nn.Module):
+ def __init__(self, voxel_size, point_cloud_range, max_num_points, max_voxels):
+ super().__init__()
+ self.voxel_layer = Voxelization(voxel_size=voxel_size,
+ point_cloud_range=point_cloud_range,
+ max_num_points=max_num_points,
+ max_voxels=max_voxels)
+
+ @torch.no_grad()
+ def forward(self, batched_pts):
+ '''
+ batched_pts: list[tensor], len(batched_pts) = bs
+ return:
+ pillars: (p1 + p2 + ... + pb, num_points, c),
+ coors_batch: (p1 + p2 + ... + pb, 1 + 3),
+ num_points_per_pillar: (p1 + p2 + ... + pb, ), (b: batch size)
+ '''
+ pillars, coors, npoints_per_pillar = [], [], []
+ for i, pts in enumerate(batched_pts):
+ voxels_out, coors_out, num_points_per_voxel_out = self.voxel_layer(pts)
+ # voxels_out: (max_voxel, num_points, c), coors_out: (max_voxel, 3)
+ # num_points_per_voxel_out: (max_voxel, )
+ pillars.append(voxels_out)
+ coors.append(coors_out.long())
+ npoints_per_pillar.append(num_points_per_voxel_out)
+
+ pillars = torch.cat(pillars, dim=0) # (p1 + p2 + ... + pb, num_points, c)
+ npoints_per_pillar = torch.cat(npoints_per_pillar, dim=0) # (p1 + p2 + ... + pb, )
+ coors_batch = []
+ for i, cur_coors in enumerate(coors):
+ coors_batch.append(F.pad(cur_coors, (1, 0), value=i))
+ coors_batch = torch.cat(coors_batch, dim=0) # (p1 + p2 + ... + pb, 1 + 3)
+
+ return pillars, coors_batch, npoints_per_pillar
+
+
+class PillarEncoder(nn.Module):
+ def __init__(self, voxel_size, point_cloud_range, in_channel, out_channel):
+ super().__init__()
+ self.out_channel = out_channel
+ self.vx, self.vy = voxel_size[0], voxel_size[1]
+ self.x_offset = voxel_size[0] / 2 + point_cloud_range[0]
+ self.y_offset = voxel_size[1] / 2 + point_cloud_range[1]
+ self.x_l = int((point_cloud_range[3] - point_cloud_range[0]) / voxel_size[0])
+ self.y_l = int((point_cloud_range[4] - point_cloud_range[1]) / voxel_size[1])
+
+ self.conv = nn.Conv1d(in_channel, out_channel, 1, bias=False)
+ self.bn = nn.BatchNorm1d(out_channel, eps=1e-3, momentum=0.01)
+
+ def forward(self, pillars, coors_batch, npoints_per_pillar):
+ '''
+ pillars: (p1 + p2 + ... + pb, num_points, c), c = 4
+ coors_batch: (p1 + p2 + ... + pb, 1 + 3)
+ npoints_per_pillar: (p1 + p2 + ... + pb, )
+ return: (bs, out_channel, y_l, x_l)
+ '''
+ device = pillars.device
+ # 1. calculate offset to the points center (in each pillar)
+ offset_pt_center = pillars[:, :, :3] - torch.sum(pillars[:, :, :3], dim=1, keepdim=True) / npoints_per_pillar[:, None, None] # (p1 + p2 + ... + pb, num_points, 3)
+
+ # 2. calculate offset to the pillar center
+ x_offset_pi_center = pillars[:, :, :1] - (coors_batch[:, None, 1:2] * self.vx + self.x_offset) # (p1 + p2 + ... + pb, num_points, 1)
+ y_offset_pi_center = pillars[:, :, 1:2] - (coors_batch[:, None, 2:3] * self.vy + self.y_offset) # (p1 + p2 + ... + pb, num_points, 1)
+
+ # 3. encoder
+ features = torch.cat([pillars, offset_pt_center, x_offset_pi_center, y_offset_pi_center], dim=-1) # (p1 + p2 + ... + pb, num_points, 9)
+ features[:, :, 0:1] = x_offset_pi_center # tmp
+ features[:, :, 1:2] = y_offset_pi_center # tmp
+ # In consitent with mmdet3d.
+ # The reason can be referenced to https://github.com/open-mmlab/mmdetection3d/issues/1150
+
+ # 4. find mask for (0, 0, 0) and update the encoded features
+ # a very beautiful implementation
+ voxel_ids = torch.arange(0, pillars.size(1)).to(device) # (num_points, )
+ mask = voxel_ids[:, None] < npoints_per_pillar[None, :] # (num_points, p1 + p2 + ... + pb)
+ mask = mask.permute(1, 0).contiguous() # (p1 + p2 + ... + pb, num_points)
+ features *= mask[:, :, None]
+
+ # 5. embedding
+ features = features.permute(0, 2, 1).contiguous() # (p1 + p2 + ... + pb, 9, num_points)
+ features = F.relu(self.bn(self.conv(features))) # (p1 + p2 + ... + pb, out_channels, num_points)
+ pooling_features = torch.max(features, dim=-1)[0] # (p1 + p2 + ... + pb, out_channels)
+
+ # 6. pillar scatter
+ batched_canvas = []
+ bs = coors_batch[-1, 0] + 1
+ for i in range(bs):
+ cur_coors_idx = coors_batch[:, 0] == i
+ cur_coors = coors_batch[cur_coors_idx, :]
+ cur_features = pooling_features[cur_coors_idx]
+
+ canvas = torch.zeros((self.x_l, self.y_l, self.out_channel), dtype=torch.float32, device=device)
+ canvas[cur_coors[:, 1], cur_coors[:, 2]] = cur_features
+ canvas = canvas.permute(2, 1, 0).contiguous()
+ batched_canvas.append(canvas)
+ batched_canvas = torch.stack(batched_canvas, dim=0) # (bs, in_channel, self.y_l, self.x_l)
+ return batched_canvas
+
+
+class Backbone(nn.Module):
+ def __init__(self, in_channel, out_channels, layer_nums, layer_strides=[2, 2, 2]):
+ super().__init__()
+ assert len(out_channels) == len(layer_nums)
+ assert len(out_channels) == len(layer_strides)
+
+ self.multi_blocks = nn.ModuleList()
+ for i in range(len(layer_strides)):
+ blocks = []
+ blocks.append(nn.Conv2d(in_channel, out_channels[i], 3, stride=layer_strides[i], bias=False, padding=1))
+ blocks.append(nn.BatchNorm2d(out_channels[i], eps=1e-3, momentum=0.01))
+ blocks.append(nn.ReLU(inplace=True))
+
+ for _ in range(layer_nums[i]):
+ blocks.append(nn.Conv2d(out_channels[i], out_channels[i], 3, bias=False, padding=1))
+ blocks.append(nn.BatchNorm2d(out_channels[i], eps=1e-3, momentum=0.01))
+ blocks.append(nn.ReLU(inplace=True))
+
+ in_channel = out_channels[i]
+ self.multi_blocks.append(nn.Sequential(*blocks))
+
+ # in consitent with mmdet3d
+ for m in self.modules():
+ if isinstance(m, nn.Conv2d):
+ nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu')
+
+ def forward(self, x):
+ '''
+ x: (b, c, y_l, x_l). Default: (6, 64, 496, 432)
+ return: list[]. Default: [(6, 64, 248, 216), (6, 128, 124, 108), (6, 256, 62, 54)]
+ '''
+ outs = []
+ for i in range(len(self.multi_blocks)):
+ x = self.multi_blocks[i](x)
+ outs.append(x)
+ return outs
+
+
+class Neck(nn.Module):
+ def __init__(self, in_channels, upsample_strides, out_channels):
+ super().__init__()
+ assert len(in_channels) == len(upsample_strides)
+ assert len(upsample_strides) == len(out_channels)
+
+ self.decoder_blocks = nn.ModuleList()
+ for i in range(len(in_channels)):
+ decoder_block = []
+ decoder_block.append(nn.ConvTranspose2d(in_channels[i],
+ out_channels[i],
+ upsample_strides[i],
+ stride=upsample_strides[i],
+ bias=False))
+ decoder_block.append(nn.BatchNorm2d(out_channels[i], eps=1e-3, momentum=0.01))
+ decoder_block.append(nn.ReLU(inplace=True))
+
+ self.decoder_blocks.append(nn.Sequential(*decoder_block))
+
+ # in consitent with mmdet3d
+ for m in self.modules():
+ if isinstance(m, nn.ConvTranspose2d):
+ nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu')
+
+ def forward(self, x):
+ '''
+ x: [(bs, 64, 248, 216), (bs, 128, 124, 108), (bs, 256, 62, 54)]
+ return: (bs, 384, 248, 216)
+ '''
+ outs = []
+ for i in range(len(self.decoder_blocks)):
+ xi = self.decoder_blocks[i](x[i]) # (bs, 128, 248, 216)
+ outs.append(xi)
+ out = torch.cat(outs, dim=1)
+ return out
+
+
+class Head(nn.Module):
+ def __init__(self, in_channel, n_anchors, n_classes):
+ super().__init__()
+
+ self.conv_cls = nn.Conv2d(in_channel, n_anchors*n_classes, 1)
+ self.conv_reg = nn.Conv2d(in_channel, n_anchors*7, 1)
+ self.conv_dir_cls = nn.Conv2d(in_channel, n_anchors*2, 1)
+
+ # in consitent with mmdet3d
+ conv_layer_id = 0
+ for m in self.modules():
+ if isinstance(m, nn.Conv2d):
+ nn.init.normal_(m.weight, mean=0, std=0.01)
+ if conv_layer_id == 0:
+ prior_prob = 0.01
+ bias_init = float(-np.log((1 - prior_prob) / prior_prob))
+ nn.init.constant_(m.bias, bias_init)
+ else:
+ nn.init.constant_(m.bias, 0)
+ conv_layer_id += 1
+
+ def forward(self, x):
+ '''
+ x: (bs, 384, 248, 216)
+ return:
+ bbox_cls_pred: (bs, n_anchors*3, 248, 216)
+ bbox_pred: (bs, n_anchors*7, 248, 216)
+ bbox_dir_cls_pred: (bs, n_anchors*2, 248, 216)
+ '''
+ bbox_cls_pred = self.conv_cls(x)
+ bbox_pred = self.conv_reg(x)
+ bbox_dir_cls_pred = self.conv_dir_cls(x)
+ return bbox_cls_pred, bbox_pred, bbox_dir_cls_pred
+
+
+class PointPillars(nn.Module):
+ def __init__(self,
+ nclasses=3,
+ voxel_size=[0.16, 0.16, 4],
+ point_cloud_range=[0, -39.68, -3, 69.12, 39.68, 1],
+ max_num_points=32,
+ max_voxels=(16000, 40000)):
+ super().__init__()
+ self.nclasses = nclasses
+ self.pillar_layer = PillarLayer(voxel_size=voxel_size,
+ point_cloud_range=point_cloud_range,
+ max_num_points=max_num_points,
+ max_voxels=max_voxels)
+ self.pillar_encoder = PillarEncoder(voxel_size=voxel_size,
+ point_cloud_range=point_cloud_range,
+ in_channel=9,
+ out_channel=64)
+ self.backbone = Backbone(in_channel=64,
+ out_channels=[64, 128, 256],
+ layer_nums=[3, 5, 5])
+ self.neck = Neck(in_channels=[64, 128, 256],
+ upsample_strides=[1, 2, 4],
+ out_channels=[128, 128, 128])
+ self.head = Head(in_channel=384, n_anchors=2*nclasses, n_classes=nclasses)
+
+ # anchors
+ ranges = [[0, -39.68, -0.6, 69.12, 39.68, -0.6],
+ [0, -39.68, -0.6, 69.12, 39.68, -0.6],
+ [0, -39.68, -1.78, 69.12, 39.68, -1.78]]
+ sizes = [[0.6, 0.8, 1.73], [0.6, 1.76, 1.73], [1.6, 3.9, 1.56]]
+ rotations=[0, 1.57]
+ self.anchors_generator = Anchors(ranges=ranges,
+ sizes=sizes,
+ rotations=rotations)
+
+ # train
+ self.assigners = [
+ {'pos_iou_thr': 0.5, 'neg_iou_thr': 0.35, 'min_iou_thr': 0.35},
+ {'pos_iou_thr': 0.5, 'neg_iou_thr': 0.35, 'min_iou_thr': 0.35},
+ {'pos_iou_thr': 0.6, 'neg_iou_thr': 0.45, 'min_iou_thr': 0.45},
+ ]
+
+ # val and test
+ self.nms_pre = 100
+ self.nms_thr = 0.01
+ self.score_thr = 0.1
+ self.max_num = 50
+
+ def get_predicted_bboxes_single(self, bbox_cls_pred, bbox_pred, bbox_dir_cls_pred, anchors):
+ '''
+ bbox_cls_pred: (n_anchors*3, 248, 216)
+ bbox_pred: (n_anchors*7, 248, 216)
+ bbox_dir_cls_pred: (n_anchors*2, 248, 216)
+ anchors: (y_l, x_l, 3, 2, 7)
+ return:
+ bboxes: (k, 7)
+ labels: (k, )
+ scores: (k, )
+ '''
+ # 0. pre-process
+ bbox_cls_pred = bbox_cls_pred.permute(1, 2, 0).reshape(-1, self.nclasses)
+ bbox_pred = bbox_pred.permute(1, 2, 0).reshape(-1, 7)
+ bbox_dir_cls_pred = bbox_dir_cls_pred.permute(1, 2, 0).reshape(-1, 2)
+ anchors = anchors.reshape(-1, 7)
+
+ bbox_cls_pred = torch.sigmoid(bbox_cls_pred)
+ bbox_dir_cls_pred = torch.max(bbox_dir_cls_pred, dim=1)[1]
+
+ # 1. obtain self.nms_pre bboxes based on scores
+ inds = bbox_cls_pred.max(1)[0].topk(self.nms_pre)[1]
+ bbox_cls_pred = bbox_cls_pred[inds]
+ bbox_pred = bbox_pred[inds]
+ bbox_dir_cls_pred = bbox_dir_cls_pred[inds]
+ anchors = anchors[inds]
+
+ # 2. decode predicted offsets to bboxes
+ bbox_pred = anchors2bboxes(anchors, bbox_pred)
+
+ # 3. nms
+ bbox_pred2d_xy = bbox_pred[:, [0, 1]]
+ bbox_pred2d_lw = bbox_pred[:, [3, 4]]
+ bbox_pred2d = torch.cat([bbox_pred2d_xy - bbox_pred2d_lw / 2,
+ bbox_pred2d_xy + bbox_pred2d_lw / 2,
+ bbox_pred[:, 6:]], dim=-1) # (n_anchors, 5)
+
+ ret_bboxes, ret_labels, ret_scores = [], [], []
+ for i in range(self.nclasses):
+ # 3.1 filter bboxes with scores below self.score_thr
+ cur_bbox_cls_pred = bbox_cls_pred[:, i]
+ score_inds = cur_bbox_cls_pred > self.score_thr
+ if score_inds.sum() == 0:
+ continue
+
+ cur_bbox_cls_pred = cur_bbox_cls_pred[score_inds]
+ cur_bbox_pred2d = bbox_pred2d[score_inds]
+ cur_bbox_pred = bbox_pred[score_inds]
+ cur_bbox_dir_cls_pred = bbox_dir_cls_pred[score_inds]
+
+ # 3.2 nms core
+ keep_inds = nms_cuda(boxes=cur_bbox_pred2d,
+ scores=cur_bbox_cls_pred,
+ thresh=self.nms_thr,
+ pre_maxsize=None,
+ post_max_size=None)
+
+ cur_bbox_cls_pred = cur_bbox_cls_pred[keep_inds]
+ cur_bbox_pred = cur_bbox_pred[keep_inds]
+ cur_bbox_dir_cls_pred = cur_bbox_dir_cls_pred[keep_inds]
+ cur_bbox_pred[:, -1] = limit_period(cur_bbox_pred[:, -1].detach().cpu(), 1, np.pi).to(cur_bbox_pred) # [-pi, 0]
+ cur_bbox_pred[:, -1] += (1 - cur_bbox_dir_cls_pred) * np.pi
+
+ ret_bboxes.append(cur_bbox_pred)
+ ret_labels.append(torch.zeros_like(cur_bbox_pred[:, 0], dtype=torch.long) + i)
+ ret_scores.append(cur_bbox_cls_pred)
+
+ # 4. filter some bboxes if bboxes number is above self.max_num
+ if len(ret_bboxes) == 0:
+ return [], [], []
+ ret_bboxes = torch.cat(ret_bboxes, 0)
+ ret_labels = torch.cat(ret_labels, 0)
+ ret_scores = torch.cat(ret_scores, 0)
+ if ret_bboxes.size(0) > self.max_num:
+ final_inds = ret_scores.topk(self.max_num)[1]
+ ret_bboxes = ret_bboxes[final_inds]
+ ret_labels = ret_labels[final_inds]
+ ret_scores = ret_scores[final_inds]
+ result = {
+ 'lidar_bboxes': ret_bboxes.detach().cpu().numpy(),
+ 'labels': ret_labels.detach().cpu().numpy(),
+ 'scores': ret_scores.detach().cpu().numpy()
+ }
+ return result
+
+
+ def get_predicted_bboxes(self, bbox_cls_pred, bbox_pred, bbox_dir_cls_pred, batched_anchors):
+ '''
+ bbox_cls_pred: (bs, n_anchors*3, 248, 216)
+ bbox_pred: (bs, n_anchors*7, 248, 216)
+ bbox_dir_cls_pred: (bs, n_anchors*2, 248, 216)
+ batched_anchors: (bs, y_l, x_l, 3, 2, 7)
+ return:
+ bboxes: [(k1, 7), (k2, 7), ... ]
+ labels: [(k1, ), (k2, ), ... ]
+ scores: [(k1, ), (k2, ), ... ]
+ '''
+ results = []
+ bs = bbox_cls_pred.size(0)
+ for i in range(bs):
+ result = self.get_predicted_bboxes_single(bbox_cls_pred=bbox_cls_pred[i],
+ bbox_pred=bbox_pred[i],
+ bbox_dir_cls_pred=bbox_dir_cls_pred[i],
+ anchors=batched_anchors[i])
+ results.append(result)
+ return results
+
+ def forward(self, batched_pts, mode='test', batched_gt_bboxes=None, batched_gt_labels=None):
+ batch_size = len(batched_pts)
+ # batched_pts: list[tensor] -> pillars: (p1 + p2 + ... + pb, num_points, c),
+ # coors_batch: (p1 + p2 + ... + pb, 1 + 3),
+ # num_points_per_pillar: (p1 + p2 + ... + pb, ), (b: batch size)
+ pillars, coors_batch, npoints_per_pillar = self.pillar_layer(batched_pts)
+
+ # pillars: (p1 + p2 + ... + pb, num_points, c), c = 4
+ # coors_batch: (p1 + p2 + ... + pb, 1 + 3)
+ # npoints_per_pillar: (p1 + p2 + ... + pb, )
+ # -> pillar_features: (bs, out_channel, y_l, x_l)
+ pillar_features = self.pillar_encoder(pillars, coors_batch, npoints_per_pillar)
+
+ # xs: [(bs, 64, 248, 216), (bs, 128, 124, 108), (bs, 256, 62, 54)]
+ xs = self.backbone(pillar_features)
+
+ # x: (bs, 384, 248, 216)
+ x = self.neck(xs)
+
+ # bbox_cls_pred: (bs, n_anchors*3, 248, 216)
+ # bbox_pred: (bs, n_anchors*7, 248, 216)
+ # bbox_dir_cls_pred: (bs, n_anchors*2, 248, 216)
+ bbox_cls_pred, bbox_pred, bbox_dir_cls_pred = self.head(x)
+
+ # anchors
+ device = bbox_cls_pred.device
+ feature_map_size = torch.tensor(list(bbox_cls_pred.size()[-2:]), device=device)
+ anchors = self.anchors_generator.get_multi_anchors(feature_map_size)
+ batched_anchors = [anchors for _ in range(batch_size)]
+
+ if mode == 'train':
+ anchor_target_dict = anchor_target(batched_anchors=batched_anchors,
+ batched_gt_bboxes=batched_gt_bboxes,
+ batched_gt_labels=batched_gt_labels,
+ assigners=self.assigners,
+ nclasses=self.nclasses)
+
+ return bbox_cls_pred, bbox_pred, bbox_dir_cls_pred, anchor_target_dict
+ elif mode == 'val':
+ results = self.get_predicted_bboxes(bbox_cls_pred=bbox_cls_pred,
+ bbox_pred=bbox_pred,
+ bbox_dir_cls_pred=bbox_dir_cls_pred,
+ batched_anchors=batched_anchors)
+ return results
+
+ elif mode == 'test':
+ results = self.get_predicted_bboxes(bbox_cls_pred=bbox_cls_pred,
+ bbox_pred=bbox_pred,
+ bbox_dir_cls_pred=bbox_dir_cls_pred,
+ batched_anchors=batched_anchors)
+ return results
+ else:
+ raise ValueError
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/__init__.py b/notebooks/3D-point-pillars/pointpillars/ops/__init__.py
new file mode 100644
index 00000000000..e4469056bab
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/__init__.py
@@ -0,0 +1,2 @@
+from .voxel_module import Voxelization
+from .iou3d_module import boxes_iou_bev, nms_cuda, boxes_overlap_bev
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d.cpp b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d.cpp
new file mode 100644
index 00000000000..77a4543fc88
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d.cpp
@@ -0,0 +1,275 @@
+// Modified from
+// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms.cpp
+
+/*
+3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)
+Written by Shaoshuai Shi
+All Rights Reserved 2019-2020.
+*/
+
+#ifdef WITH_CUDA
+#include
+#include
+#endif // WITH_CUDA
+#include
+#include
+
+#include
+#include
+
+#ifndef WITH_CUDA
+#include
+#include
+#endif // !WITH_CUDA
+
+#ifdef WITH_CUDA
+#define CHECK_CUDA(x) \
+ TORCH_CHECK(x.device().is_cuda(), #x, " must be a CUDAtensor ")
+#else
+#define CHECK_CUDA(x) // No-op for CPU builds
+// #define CHECK_CUDA(x) \
+// TORCH_CHECK(x.device().is_cpu(), #x, " must be a CPU tensor")
+#endif // WITH_CUDA
+#define CHECK_CONTIGUOUS(x) \
+ TORCH_CHECK(x.is_contiguous(), #x, " must be contiguous ")
+#define CHECK_INPUT(x) \
+ CHECK_CUDA(x); \
+ CHECK_CONTIGUOUS(x)
+
+#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))
+
+#ifdef WITH_CUDA
+#define CHECK_ERROR(ans) \
+ { gpuAssert((ans), __FILE__, __LINE__); }
+inline void gpuAssert(cudaError_t code, const char *file, int line,
+ bool abort = true) {
+ if (code != cudaSuccess) {
+ fprintf(stderr, "GPUassert: %s %s %d\n", cudaGetErrorString(code), file,
+ line);
+ if (abort) exit(code);
+ }
+}
+#else // CPU build
+#define CHECK_ERROR(ans) { cpuAssert((ans), __FILE__, __LINE__); }
+inline void cpuAssert(bool success, const char *file, int line, bool abort = true) {
+ if (!success) {
+ fprintf(stderr, "CPUassert: %s %d\n", file, line);
+ if (abort) exit(EXIT_FAILURE);
+ }
+}
+#endif
+
+const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
+
+void boxesoverlapLauncher(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_overlap);
+void boxesioubevLauncher(const int num_a, const float *boxes_a, const int num_b,
+ const float *boxes_b, float *ans_iou);
+void nmsLauncher(const float *boxes, unsigned long long *mask, int boxes_num,
+ float nms_overlap_thresh);
+void nmsNormalLauncher(const float *boxes, unsigned long long *mask,
+ int boxes_num, float nms_overlap_thresh);
+
+int boxes_overlap_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,
+ at::Tensor ans_overlap) {
+ // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]
+ // params boxes_b: (M, 5)
+ // params ans_overlap: (N, M)
+
+ CHECK_INPUT(boxes_a);
+ CHECK_INPUT(boxes_b);
+ CHECK_INPUT(ans_overlap);
+
+ int num_a = boxes_a.size(0);
+ int num_b = boxes_b.size(0);
+
+ const float *boxes_a_data = boxes_a.data_ptr();
+ const float *boxes_b_data = boxes_b.data_ptr();
+ float *ans_overlap_data = ans_overlap.data_ptr();
+
+ boxesoverlapLauncher(num_a, boxes_a_data, num_b, boxes_b_data,
+ ans_overlap_data);
+
+ return 1;
+}
+
+int boxes_iou_bev_gpu(at::Tensor boxes_a, at::Tensor boxes_b,
+ at::Tensor ans_iou) {
+ // params boxes_a: (N, 5) [x1, y1, x2, y2, ry]
+ // params boxes_b: (M, 5)
+ // params ans_overlap: (N, M)
+
+ CHECK_INPUT(boxes_a);
+ CHECK_INPUT(boxes_b);
+ CHECK_INPUT(ans_iou);
+
+ int num_a = boxes_a.size(0);
+ int num_b = boxes_b.size(0);
+
+ const float *boxes_a_data = boxes_a.data_ptr();
+ const float *boxes_b_data = boxes_b.data_ptr();
+ float *ans_iou_data = ans_iou.data_ptr();
+
+ boxesioubevLauncher(num_a, boxes_a_data, num_b, boxes_b_data, ans_iou_data);
+
+ return 1;
+}
+
+int nms_gpu(at::Tensor boxes, at::Tensor keep,
+ float nms_overlap_thresh, int device_id) {
+ // params boxes: (N, 5) [x1, y1, x2, y2, ry]
+ // params keep: (N)
+
+ CHECK_INPUT(boxes);
+ CHECK_CONTIGUOUS(keep);
+
+ int boxes_num = boxes.size(0);
+ const float *boxes_data = boxes.data_ptr();
+ int64_t *keep_data = keep.data_ptr();
+
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+
+#ifdef WITH_CUDA
+ cudaSetDevice(device_id);
+ unsigned long long *mask_data = NULL;
+ CHECK_ERROR(cudaMalloc((void **)&mask_data,
+ boxes_num * col_blocks * sizeof(unsigned long long)));
+ nmsLauncher(boxes_data, mask_data, boxes_num, nms_overlap_thresh);
+
+ // unsigned long long mask_cpu[boxes_num * col_blocks];
+ // unsigned long long *mask_cpu = new unsigned long long [boxes_num *
+ // col_blocks];
+ std::vector mask_cpu(boxes_num * col_blocks);
+
+ // printf("boxes_num=%d, col_blocks=%d\n", boxes_num, col_blocks);
+ CHECK_ERROR(cudaMemcpy(&mask_cpu[0], mask_data,
+ boxes_num * col_blocks * sizeof(unsigned long long),
+ cudaMemcpyDeviceToHost));
+
+ cudaFree(mask_data);
+
+ unsigned long long *remv_cpu = new unsigned long long[col_blocks]();
+
+ int num_to_keep = 0;
+
+ for (int i = 0; i < boxes_num; i++) {
+ int nblock = i / THREADS_PER_BLOCK_NMS;
+ int inblock = i % THREADS_PER_BLOCK_NMS;
+
+ if (!(remv_cpu[nblock] & (1ULL << inblock))) {
+ keep_data[num_to_keep++] = i;
+ unsigned long long *p = &mask_cpu[0] + i * col_blocks;
+ for (int j = nblock; j < col_blocks; j++) {
+ remv_cpu[j] |= p[j];
+ }
+ }
+ }
+ delete[] remv_cpu;
+ if (cudaSuccess != cudaGetLastError()) printf("Error!\n");
+#else
+ unsigned long long *mask_cpu = new unsigned long long[boxes_num * col_blocks];
+ nmsLauncher(boxes_data, mask_cpu, boxes_num, nms_overlap_thresh);
+
+ unsigned long long *remv_cpu = new unsigned long long[col_blocks]();
+ int num_to_keep = 0;
+ for (int i = 0; i < boxes_num; ++i) {
+ int nblock = i / THREADS_PER_BLOCK_NMS;
+ int inblock = i % THREADS_PER_BLOCK_NMS;
+ if (!(remv_cpu[nblock] & (1ULL << inblock))) {
+ keep_data[num_to_keep++] = i;
+ unsigned long long *p = mask_cpu + i * col_blocks;
+ for (int j = nblock; j < col_blocks; ++j) {
+ remv_cpu[j] |= p[j];
+ }
+ }
+ }
+ delete[] remv_cpu;
+ delete[] mask_cpu;
+#endif
+
+ return num_to_keep;
+}
+
+int nms_normal_gpu(at::Tensor boxes, at::Tensor keep,
+ float nms_overlap_thresh, int device_id) {
+ // params boxes: (N, 5) [x1, y1, x2, y2, ry]
+ // params keep: (N)
+
+ CHECK_INPUT(boxes);
+ CHECK_CONTIGUOUS(keep);
+
+ int boxes_num = boxes.size(0);
+ const float *boxes_data = boxes.data_ptr();
+ int64_t *keep_data = keep.data_ptr();
+
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+
+#ifdef WITH_CUDA
+ cudaSetDevice(device_id);
+ unsigned long long *mask_data = NULL;
+ CHECK_ERROR(cudaMalloc((void **)&mask_data,
+ boxes_num * col_blocks * sizeof(unsigned long long)));
+ nmsNormalLauncher(boxes_data, mask_data, boxes_num, nms_overlap_thresh);
+
+ // unsigned long long mask_cpu[boxes_num * col_blocks];
+ // unsigned long long *mask_cpu = new unsigned long long [boxes_num *
+ // col_blocks];
+ std::vector mask_cpu(boxes_num * col_blocks);
+
+ // printf("boxes_num=%d, col_blocks=%d\n", boxes_num, col_blocks);
+ CHECK_ERROR(cudaMemcpy(&mask_cpu[0], mask_data,
+ boxes_num * col_blocks * sizeof(unsigned long long),
+ cudaMemcpyDeviceToHost));
+
+ cudaFree(mask_data);
+
+ unsigned long long *remv_cpu = new unsigned long long[col_blocks]();
+
+ int num_to_keep = 0;
+
+ for (int i = 0; i < boxes_num; i++) {
+ int nblock = i / THREADS_PER_BLOCK_NMS;
+ int inblock = i % THREADS_PER_BLOCK_NMS;
+
+ if (!(remv_cpu[nblock] & (1ULL << inblock))) {
+ keep_data[num_to_keep++] = i;
+ unsigned long long *p = &mask_cpu[0] + i * col_blocks;
+ for (int j = nblock; j < col_blocks; j++) {
+ remv_cpu[j] |= p[j];
+ }
+ }
+ }
+ delete[] remv_cpu;
+ if (cudaSuccess != cudaGetLastError()) printf("Error!\n");
+#else
+ unsigned long long *mask_cpu = new unsigned long long[boxes_num * col_blocks];
+ nmsNormalLauncher(boxes_data, mask_cpu, boxes_num, nms_overlap_thresh);
+
+ unsigned long long *remv_cpu = new unsigned long long[col_blocks]();
+ int num_to_keep = 0;
+ for (int i = 0; i < boxes_num; ++i) {
+ int nblock = i / THREADS_PER_BLOCK_NMS;
+ int inblock = i % THREADS_PER_BLOCK_NMS;
+ if (!(remv_cpu[nblock] & (1ULL << inblock))) {
+ keep_data[num_to_keep++] = i;
+ unsigned long long *p = mask_cpu + i * col_blocks;
+ for (int j = nblock; j < col_blocks; ++j) {
+ remv_cpu[j] |= p[j];
+ }
+ }
+ }
+ delete[] remv_cpu;
+ delete[] mask_cpu;
+#endif
+
+ return num_to_keep;
+}
+
+PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
+ m.def("boxes_overlap_bev_gpu", &boxes_overlap_bev_gpu,
+ "oriented boxes overlap");
+ m.def("boxes_iou_bev_gpu", &boxes_iou_bev_gpu, "oriented boxes iou");
+ m.def("nms_gpu", &nms_gpu, "oriented nms gpu");
+ m.def("nms_normal_gpu", &nms_normal_gpu, "nms gpu");
+}
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel.cu b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel.cu
new file mode 100644
index 00000000000..861aea3c5a1
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel.cu
@@ -0,0 +1,439 @@
+// Modified from
+// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu
+
+/*
+3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)
+Written by Shaoshuai Shi
+All Rights Reserved 2019-2020.
+*/
+
+#include
+#define THREADS_PER_BLOCK 16
+#define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0))
+
+//#define DEBUG
+const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
+__device__ const float EPS = 1e-8;
+struct Point {
+ float x, y;
+ __device__ Point() {}
+ __device__ Point(double _x, double _y) { x = _x, y = _y; }
+
+ __device__ void set(float _x, float _y) {
+ x = _x;
+ y = _y;
+ }
+
+ __device__ Point operator+(const Point &b) const {
+ return Point(x + b.x, y + b.y);
+ }
+
+ __device__ Point operator-(const Point &b) const {
+ return Point(x - b.x, y - b.y);
+ }
+};
+
+__device__ inline float cross(const Point &a, const Point &b) {
+ return a.x * b.y - a.y * b.x;
+}
+
+__device__ inline float cross(const Point &p1, const Point &p2,
+ const Point &p0) {
+ return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y);
+}
+
+__device__ int check_rect_cross(const Point &p1, const Point &p2,
+ const Point &q1, const Point &q2) {
+ int ret = min(p1.x, p2.x) <= max(q1.x, q2.x) &&
+ min(q1.x, q2.x) <= max(p1.x, p2.x) &&
+ min(p1.y, p2.y) <= max(q1.y, q2.y) &&
+ min(q1.y, q2.y) <= max(p1.y, p2.y);
+ return ret;
+}
+
+__device__ inline int check_in_box2d(const float *box, const Point &p) {
+ // params: box (5) [x1, y1, x2, y2, angle]
+ const float MARGIN = 1e-5;
+
+ float center_x = (box[0] + box[2]) / 2;
+ float center_y = (box[1] + box[3]) / 2;
+ float angle_cos = cos(-box[4]),
+ angle_sin =
+ sin(-box[4]); // rotate the point in the opposite direction of box
+ float rot_x =
+ (p.x - center_x) * angle_cos + (p.y - center_y) * angle_sin + center_x;
+ float rot_y =
+ -(p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos + center_y;
+#ifdef DEBUG
+ printf("box: (%.3f, %.3f, %.3f, %.3f, %.3f)\n", box[0], box[1], box[2],
+ box[3], box[4]);
+ printf(
+ "center: (%.3f, %.3f), cossin(%.3f, %.3f), src(%.3f, %.3f), rot(%.3f, "
+ "%.3f)\n",
+ center_x, center_y, angle_cos, angle_sin, p.x, p.y, rot_x, rot_y);
+#endif
+ return (rot_x > box[0] - MARGIN && rot_x < box[2] + MARGIN &&
+ rot_y > box[1] - MARGIN && rot_y < box[3] + MARGIN);
+}
+
+__device__ inline int intersection(const Point &p1, const Point &p0,
+ const Point &q1, const Point &q0,
+ Point &ans) {
+ // fast exclusion
+ if (check_rect_cross(p0, p1, q0, q1) == 0) return 0;
+
+ // check cross standing
+ float s1 = cross(q0, p1, p0);
+ float s2 = cross(p1, q1, p0);
+ float s3 = cross(p0, q1, q0);
+ float s4 = cross(q1, p1, q0);
+
+ if (!(s1 * s2 > 0 && s3 * s4 > 0)) return 0;
+
+ // calculate intersection of two lines
+ float s5 = cross(q1, p1, p0);
+ if (fabs(s5 - s1) > EPS) {
+ ans.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1);
+ ans.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1);
+
+ } else {
+ float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y;
+ float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y;
+ float D = a0 * b1 - a1 * b0;
+
+ ans.x = (b0 * c1 - b1 * c0) / D;
+ ans.y = (a1 * c0 - a0 * c1) / D;
+ }
+
+ return 1;
+}
+
+__device__ inline void rotate_around_center(const Point ¢er,
+ const float angle_cos,
+ const float angle_sin, Point &p) {
+ float new_x =
+ (p.x - center.x) * angle_cos + (p.y - center.y) * angle_sin + center.x;
+ float new_y =
+ -(p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y;
+ p.set(new_x, new_y);
+}
+
+__device__ inline int point_cmp(const Point &a, const Point &b,
+ const Point ¢er) {
+ return atan2(a.y - center.y, a.x - center.x) >
+ atan2(b.y - center.y, b.x - center.x);
+}
+
+__device__ inline float box_overlap(const float *box_a, const float *box_b) {
+ // params: box_a (5) [x1, y1, x2, y2, angle]
+ // params: box_b (5) [x1, y1, x2, y2, angle]
+
+ float a_x1 = box_a[0], a_y1 = box_a[1], a_x2 = box_a[2], a_y2 = box_a[3],
+ a_angle = box_a[4];
+ float b_x1 = box_b[0], b_y1 = box_b[1], b_x2 = box_b[2], b_y2 = box_b[3],
+ b_angle = box_b[4];
+
+ Point center_a((a_x1 + a_x2) / 2, (a_y1 + a_y2) / 2);
+ Point center_b((b_x1 + b_x2) / 2, (b_y1 + b_y2) / 2);
+#ifdef DEBUG
+ printf(
+ "a: (%.3f, %.3f, %.3f, %.3f, %.3f), b: (%.3f, %.3f, %.3f, %.3f, %.3f)\n",
+ a_x1, a_y1, a_x2, a_y2, a_angle, b_x1, b_y1, b_x2, b_y2, b_angle);
+ printf("center a: (%.3f, %.3f), b: (%.3f, %.3f)\n", center_a.x, center_a.y,
+ center_b.x, center_b.y);
+#endif
+
+ Point box_a_corners[5];
+ box_a_corners[0].set(a_x1, a_y1);
+ box_a_corners[1].set(a_x2, a_y1);
+ box_a_corners[2].set(a_x2, a_y2);
+ box_a_corners[3].set(a_x1, a_y2);
+
+ Point box_b_corners[5];
+ box_b_corners[0].set(b_x1, b_y1);
+ box_b_corners[1].set(b_x2, b_y1);
+ box_b_corners[2].set(b_x2, b_y2);
+ box_b_corners[3].set(b_x1, b_y2);
+
+ // get oriented corners
+ float a_angle_cos = cos(a_angle), a_angle_sin = sin(a_angle);
+ float b_angle_cos = cos(b_angle), b_angle_sin = sin(b_angle);
+
+ for (int k = 0; k < 4; k++) {
+#ifdef DEBUG
+ printf("before corner %d: a(%.3f, %.3f), b(%.3f, %.3f) \n", k,
+ box_a_corners[k].x, box_a_corners[k].y, box_b_corners[k].x,
+ box_b_corners[k].y);
+#endif
+ rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]);
+ rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]);
+#ifdef DEBUG
+ printf("corner %d: a(%.3f, %.3f), b(%.3f, %.3f) \n", k, box_a_corners[k].x,
+ box_a_corners[k].y, box_b_corners[k].x, box_b_corners[k].y);
+#endif
+ }
+
+ box_a_corners[4] = box_a_corners[0];
+ box_b_corners[4] = box_b_corners[0];
+
+ // get intersection of lines
+ Point cross_points[16];
+ Point poly_center;
+ int cnt = 0, flag = 0;
+
+ poly_center.set(0, 0);
+ for (int i = 0; i < 4; i++) {
+ for (int j = 0; j < 4; j++) {
+ flag = intersection(box_a_corners[i + 1], box_a_corners[i],
+ box_b_corners[j + 1], box_b_corners[j],
+ cross_points[cnt]);
+ if (flag) {
+ poly_center = poly_center + cross_points[cnt];
+ cnt++;
+ }
+ }
+ }
+
+ // check corners
+ for (int k = 0; k < 4; k++) {
+ if (check_in_box2d(box_a, box_b_corners[k])) {
+ poly_center = poly_center + box_b_corners[k];
+ cross_points[cnt] = box_b_corners[k];
+ cnt++;
+ }
+ if (check_in_box2d(box_b, box_a_corners[k])) {
+ poly_center = poly_center + box_a_corners[k];
+ cross_points[cnt] = box_a_corners[k];
+ cnt++;
+ }
+ }
+
+ poly_center.x /= cnt;
+ poly_center.y /= cnt;
+
+ // sort the points of polygon
+ Point temp;
+ for (int j = 0; j < cnt - 1; j++) {
+ for (int i = 0; i < cnt - j - 1; i++) {
+ if (point_cmp(cross_points[i], cross_points[i + 1], poly_center)) {
+ temp = cross_points[i];
+ cross_points[i] = cross_points[i + 1];
+ cross_points[i + 1] = temp;
+ }
+ }
+ }
+
+#ifdef DEBUG
+ printf("cnt=%d\n", cnt);
+ for (int i = 0; i < cnt; i++) {
+ printf("All cross point %d: (%.3f, %.3f)\n", i, cross_points[i].x,
+ cross_points[i].y);
+ }
+#endif
+
+ // get the overlap areas
+ float area = 0;
+ for (int k = 0; k < cnt - 1; k++) {
+ area += cross(cross_points[k] - cross_points[0],
+ cross_points[k + 1] - cross_points[0]);
+ }
+
+ return fabs(area) / 2.0;
+}
+
+__device__ inline float iou_bev(const float *box_a, const float *box_b) {
+ // params: box_a (5) [x1, y1, x2, y2, angle]
+ // params: box_b (5) [x1, y1, x2, y2, angle]
+ float sa = (box_a[2] - box_a[0]) * (box_a[3] - box_a[1]);
+ float sb = (box_b[2] - box_b[0]) * (box_b[3] - box_b[1]);
+ float s_overlap = box_overlap(box_a, box_b);
+ return s_overlap / fmaxf(sa + sb - s_overlap, EPS);
+}
+
+__global__ void boxes_overlap_kernel(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_overlap) {
+ const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;
+ const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;
+
+ if (a_idx >= num_a || b_idx >= num_b) {
+ return;
+ }
+ const float *cur_box_a = boxes_a + a_idx * 5;
+ const float *cur_box_b = boxes_b + b_idx * 5;
+ float s_overlap = box_overlap(cur_box_a, cur_box_b);
+ ans_overlap[a_idx * num_b + b_idx] = s_overlap;
+}
+
+__global__ void boxes_iou_bev_kernel(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_iou) {
+ const int a_idx = blockIdx.y * THREADS_PER_BLOCK + threadIdx.y;
+ const int b_idx = blockIdx.x * THREADS_PER_BLOCK + threadIdx.x;
+
+ if (a_idx >= num_a || b_idx >= num_b) {
+ return;
+ }
+
+ const float *cur_box_a = boxes_a + a_idx * 5;
+ const float *cur_box_b = boxes_b + b_idx * 5;
+ float cur_iou_bev = iou_bev(cur_box_a, cur_box_b);
+ ans_iou[a_idx * num_b + b_idx] = cur_iou_bev;
+}
+
+__global__ void nms_kernel(const int boxes_num, const float nms_overlap_thresh,
+ const float *boxes, unsigned long long *mask) {
+ // params: boxes (N, 5) [x1, y1, x2, y2, ry]
+ // params: mask (N, N/THREADS_PER_BLOCK_NMS)
+
+ const int row_start = blockIdx.y;
+ const int col_start = blockIdx.x;
+
+ // if (row_start > col_start) return;
+
+ const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,
+ THREADS_PER_BLOCK_NMS);
+ const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,
+ THREADS_PER_BLOCK_NMS);
+
+ __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];
+
+ if (threadIdx.x < col_size) {
+ block_boxes[threadIdx.x * 5 + 0] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];
+ block_boxes[threadIdx.x * 5 + 1] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];
+ block_boxes[threadIdx.x * 5 + 2] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];
+ block_boxes[threadIdx.x * 5 + 3] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];
+ block_boxes[threadIdx.x * 5 + 4] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];
+ }
+ __syncthreads();
+
+ if (threadIdx.x < row_size) {
+ const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;
+ const float *cur_box = boxes + cur_box_idx * 5;
+
+ int i = 0;
+ unsigned long long t = 0;
+ int start = 0;
+ if (row_start == col_start) {
+ start = threadIdx.x + 1;
+ }
+ for (i = start; i < col_size; i++) {
+ if (iou_bev(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {
+ t |= 1ULL << i;
+ }
+ }
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+ mask[cur_box_idx * col_blocks + col_start] = t;
+ }
+}
+
+__device__ inline float iou_normal(float const *const a, float const *const b) {
+ float left = fmaxf(a[0], b[0]), right = fminf(a[2], b[2]);
+ float top = fmaxf(a[1], b[1]), bottom = fminf(a[3], b[3]);
+ float width = fmaxf(right - left, 0.f), height = fmaxf(bottom - top, 0.f);
+ float interS = width * height;
+ float Sa = (a[2] - a[0]) * (a[3] - a[1]);
+ float Sb = (b[2] - b[0]) * (b[3] - b[1]);
+ return interS / fmaxf(Sa + Sb - interS, EPS);
+}
+
+__global__ void nms_normal_kernel(const int boxes_num,
+ const float nms_overlap_thresh,
+ const float *boxes,
+ unsigned long long *mask) {
+ // params: boxes (N, 5) [x1, y1, x2, y2, ry]
+ // params: mask (N, N/THREADS_PER_BLOCK_NMS)
+
+ const int row_start = blockIdx.y;
+ const int col_start = blockIdx.x;
+
+ // if (row_start > col_start) return;
+
+ const int row_size = fminf(boxes_num - row_start * THREADS_PER_BLOCK_NMS,
+ THREADS_PER_BLOCK_NMS);
+ const int col_size = fminf(boxes_num - col_start * THREADS_PER_BLOCK_NMS,
+ THREADS_PER_BLOCK_NMS);
+
+ __shared__ float block_boxes[THREADS_PER_BLOCK_NMS * 5];
+
+ if (threadIdx.x < col_size) {
+ block_boxes[threadIdx.x * 5 + 0] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 0];
+ block_boxes[threadIdx.x * 5 + 1] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 1];
+ block_boxes[threadIdx.x * 5 + 2] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 2];
+ block_boxes[threadIdx.x * 5 + 3] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 3];
+ block_boxes[threadIdx.x * 5 + 4] =
+ boxes[(THREADS_PER_BLOCK_NMS * col_start + threadIdx.x) * 5 + 4];
+ }
+ __syncthreads();
+
+ if (threadIdx.x < row_size) {
+ const int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + threadIdx.x;
+ const float *cur_box = boxes + cur_box_idx * 5;
+
+ int i = 0;
+ unsigned long long t = 0;
+ int start = 0;
+ if (row_start == col_start) {
+ start = threadIdx.x + 1;
+ }
+ for (i = start; i < col_size; i++) {
+ if (iou_normal(cur_box, block_boxes + i * 5) > nms_overlap_thresh) {
+ t |= 1ULL << i;
+ }
+ }
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+ mask[cur_box_idx * col_blocks + col_start] = t;
+ }
+}
+
+void boxesoverlapLauncher(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_overlap) {
+ dim3 blocks(
+ DIVUP(num_b, THREADS_PER_BLOCK),
+ DIVUP(num_a, THREADS_PER_BLOCK)); // blockIdx.x(col), blockIdx.y(row)
+ dim3 threads(THREADS_PER_BLOCK, THREADS_PER_BLOCK);
+
+ boxes_overlap_kernel<<>>(num_a, boxes_a, num_b, boxes_b,
+ ans_overlap);
+#ifdef DEBUG
+ cudaDeviceSynchronize(); // for using printf in kernel function
+#endif
+}
+
+void boxesioubevLauncher(const int num_a, const float *boxes_a, const int num_b,
+ const float *boxes_b, float *ans_iou) {
+ dim3 blocks(
+ DIVUP(num_b, THREADS_PER_BLOCK),
+ DIVUP(num_a, THREADS_PER_BLOCK)); // blockIdx.x(col), blockIdx.y(row)
+ dim3 threads(THREADS_PER_BLOCK, THREADS_PER_BLOCK);
+
+ boxes_iou_bev_kernel<<>>(num_a, boxes_a, num_b, boxes_b,
+ ans_iou);
+}
+
+void nmsLauncher(const float *boxes, unsigned long long *mask, int boxes_num,
+ float nms_overlap_thresh) {
+ dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),
+ DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));
+ dim3 threads(THREADS_PER_BLOCK_NMS);
+ nms_kernel<<>>(boxes_num, nms_overlap_thresh, boxes, mask);
+}
+
+void nmsNormalLauncher(const float *boxes, unsigned long long *mask,
+ int boxes_num, float nms_overlap_thresh) {
+ dim3 blocks(DIVUP(boxes_num, THREADS_PER_BLOCK_NMS),
+ DIVUP(boxes_num, THREADS_PER_BLOCK_NMS));
+ dim3 threads(THREADS_PER_BLOCK_NMS);
+ nms_normal_kernel<<>>(boxes_num, nms_overlap_thresh, boxes,
+ mask);
+}
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel_cpu.cpp b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel_cpu.cpp
new file mode 100644
index 00000000000..39319afe00c
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/iou3d/iou3d_kernel_cpu.cpp
@@ -0,0 +1,304 @@
+// Modified from
+// https://github.com/open-mmlab/OpenPCDet/blob/master/pcdet/ops/iou3d_nms/src/iou3d_nms_kernel.cu
+// https://github.com/zhulf0804/PointPillars/blob/main/pointpillars/ops/iou3d/iou3d_kernel.cu
+
+/*
+3D IoU Calculation and Rotated NMS(modified from 2D NMS written by others)
+Written by Shaoshuai Shi
+All Rights Reserved 2019-2020.
+*/
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#define THREADS_PER_BLOCK 16
+static const int THREADS_PER_BLOCK_NMS = sizeof(unsigned long long) * 8;
+static constexpr float EPS = 1e-8f;
+#define DIVUP(m, n) (((m) / (n)) + (((m) % (n)) > 0))
+
+struct Point {
+ float x, y;
+ Point() : x(0), y(0) {}
+ Point(float _x, float _y) : x(_x), y(_y) {}
+ void set(float _x, float _y) { x = _x; y = _y; }
+ Point operator+(const Point &b) const { return Point(x + b.x, y + b.y); }
+ Point operator-(const Point &b) const { return Point(x - b.x, y - b.y); }
+};
+
+inline float cross(const Point &a, const Point &b) {
+ return a.x * b.y - a.y * b.x;
+}
+
+inline float cross(const Point &p1, const Point &p2, const Point &p0) {
+ return (p1.x - p0.x) * (p2.y - p0.y) - (p2.x - p0.x) * (p1.y - p0.y);
+}
+
+inline int check_rect_cross(const Point &p1, const Point &p2, const Point &q1, const Point &q2) {
+ int ret = std::min(p1.x, p2.x) <= std::max(q1.x, q2.x) &&
+ std::min(q1.x, q2.x) <= std::max(p1.x, p2.x) &&
+ std::min(p1.y, p2.y) <= std::max(q1.y, q2.y) &&
+ std::min(q1.y, q2.y) <= std::max(p1.y, p2.y);
+ return ret;
+}
+
+inline int check_in_box2d(const float *box, const Point &p) {
+ const float MARGIN = 1e-5f;
+ float center_x = (box[0] + box[2]) / 2.f;
+ float center_y = (box[1] + box[3]) / 2.f;
+ float angle_cos = std::cos(-box[4]), angle_sin = std::sin(-box[4]);
+ float rot_x = (p.x - center_x) * angle_cos + (p.y - center_y) * angle_sin + center_x;
+ float rot_y = -(p.x - center_x) * angle_sin + (p.y - center_y) * angle_cos + center_y;
+ return (rot_x > box[0] - MARGIN && rot_x < box[2] + MARGIN && rot_y > box[1] - MARGIN && rot_y < box[3] + MARGIN);
+}
+
+inline int intersection(const Point &p1, const Point &p0, const Point &q1, const Point &q0, Point &ans) {
+ if (check_rect_cross(p0, p1, q0, q1) == 0) return 0;
+ float s1 = cross(q0, p1, p0);
+ float s2 = cross(p1, q1, p0);
+ float s3 = cross(p0, q1, q0);
+ float s4 = cross(q1, p1, q0);
+ if (!(s1 * s2 > 0 && s3 * s4 > 0)) return 0;
+
+ float s5 = cross(q1, p1, p0);
+ if (std::fabs(s5 - s1) > EPS) {
+ ans.x = (s5 * q0.x - s1 * q1.x) / (s5 - s1);
+ ans.y = (s5 * q0.y - s1 * q1.y) / (s5 - s1);
+ } else {
+ float a0 = p0.y - p1.y, b0 = p1.x - p0.x, c0 = p0.x * p1.y - p1.x * p0.y;
+ float a1 = q0.y - q1.y, b1 = q1.x - q0.x, c1 = q0.x * q1.y - q1.x * q0.y;
+ float D = a0 * b1 - a1 * b0;
+ // If D == 0 lines are parallel; avoid division by zero: // Extra
+ if (std::fabs(D) < EPS) { // Extra
+ // fallback: use midpoint of overlapping segment // Extra
+ ans.x = (p0.x + p1.x + q0.x + q1.x) * 0.25f; // Extra
+ ans.y = (p0.y + p1.y + q0.y + q1.y) * 0.25f; // Extra
+ } else { // Extra
+ ans.x = (b0 * c1 - b1 * c0) / D;
+ ans.y = (a1 * c0 - a0 * c1) / D;
+ } // Extra
+ }
+ return 1;
+}
+
+inline void rotate_around_center(const Point ¢er, const float angle_cos, const float angle_sin, Point &p) {
+ float new_x = (p.x - center.x) * angle_cos + (p.y - center.y) * angle_sin + center.x;
+ float new_y = -(p.x - center.x) * angle_sin + (p.y - center.y) * angle_cos + center.y;
+ p.set(new_x, new_y);
+}
+
+inline bool point_cmp(const Point &a, const Point &b, const Point ¢er) {
+ return std::atan2(a.y - center.y, a.x - center.x) > std::atan2(b.y - center.y, b.x - center.x);
+}
+
+float box_overlap(const float *box_a, const float *box_b) {
+ float a_x1 = box_a[0], a_y1 = box_a[1], a_x2 = box_a[2], a_y2 = box_a[3], a_angle = box_a[4];
+ float b_x1 = box_b[0], b_y1 = box_b[1], b_x2 = box_b[2], b_y2 = box_b[3], b_angle = box_b[4];
+
+ Point center_a((a_x1 + a_x2) / 2.f, (a_y1 + a_y2) / 2.f);
+ Point center_b((b_x1 + b_x2) / 2.f, (b_y1 + b_y2) / 2.f);
+
+ Point box_a_corners[5];
+ box_a_corners[0].set(a_x1, a_y1);
+ box_a_corners[1].set(a_x2, a_y1);
+ box_a_corners[2].set(a_x2, a_y2);
+ box_a_corners[3].set(a_x1, a_y2);
+
+ Point box_b_corners[5];
+ box_b_corners[0].set(b_x1, b_y1);
+ box_b_corners[1].set(b_x2, b_y1);
+ box_b_corners[2].set(b_x2, b_y2);
+ box_b_corners[3].set(b_x1, b_y2);
+
+ float a_angle_cos = std::cos(a_angle), a_angle_sin = std::sin(a_angle);
+ float b_angle_cos = std::cos(b_angle), b_angle_sin = std::sin(b_angle);
+
+ for (int k = 0; k < 4; k++) {
+ rotate_around_center(center_a, a_angle_cos, a_angle_sin, box_a_corners[k]);
+ rotate_around_center(center_b, b_angle_cos, b_angle_sin, box_b_corners[k]);
+ }
+ box_a_corners[4] = box_a_corners[0];
+ box_b_corners[4] = box_b_corners[0];
+
+ Point cross_points[16];
+ Point poly_center;
+ int cnt = 0, flag = 0;
+ poly_center.set(0, 0);
+
+ for (int i = 0; i < 4; i++) {
+ for (int j = 0; j < 4; j++) {
+ flag = intersection(box_a_corners[i + 1], box_a_corners[i], box_b_corners[j + 1], box_b_corners[j], cross_points[cnt]);
+ if (flag) {
+ poly_center = poly_center + cross_points[cnt];
+ cnt++;
+ }
+ }
+ }
+
+ for (int k = 0; k < 4; k++) {
+ if (check_in_box2d(box_a, box_b_corners[k])) {
+ poly_center = poly_center + box_b_corners[k];
+ cross_points[cnt] = box_b_corners[k];
+ cnt++;
+ }
+ if (check_in_box2d(box_b, box_a_corners[k])) {
+ poly_center = poly_center + box_a_corners[k];
+ cross_points[cnt] = box_a_corners[k];
+ cnt++;
+ }
+ }
+
+ poly_center.x /= cnt;
+ poly_center.y /= cnt;
+
+ Point temp;
+ for (int j = 0; j < cnt - 1; j++) {
+ for (int i = 0; i < cnt - j - 1; i++) {
+ if (point_cmp(cross_points[i], cross_points[i + 1], poly_center)) {
+ temp = cross_points[i];
+ cross_points[i] = cross_points[i + 1];
+ cross_points[i + 1] = temp;
+ }
+ }
+ }
+
+ float area = 0.0f;
+ for (int k = 0; k < cnt - 1; k++) {
+ area += cross(cross_points[k] - cross_points[0],
+ cross_points[k + 1] - cross_points[0]);
+ }
+ return std::fabs(area) / 2.0f;
+}
+
+
+float iou_bev(const float *box_a, const float *box_b) {
+ float sa = (box_a[2] - box_a[0]) * (box_a[3] - box_a[1]);
+ float sb = (box_b[2] - box_b[0]) * (box_b[3] - box_b[1]);
+ float s_overlap = box_overlap(box_a, box_b);
+ return s_overlap / std::fmax(sa + sb - s_overlap, EPS);
+}
+
+void boxes_overlap_kernel(const int num_a, const float *boxes_a, const int num_b, const float *boxes_b, float *ans_overlap) {
+ // ans_overlap is expected to be length num_a * num_b, row-major: a_idx * num_b + b_idx
+ for (int a_idx = 0; a_idx < num_a; ++a_idx) {
+ const float *cur_box_a = boxes_a + a_idx * 5;
+ for (int b_idx = 0; b_idx < num_b; ++b_idx) {
+ const float *cur_box_b = boxes_b + b_idx * 5;
+ float s_overlap = box_overlap(cur_box_a, cur_box_b);
+ ans_overlap[a_idx * num_b + b_idx] = s_overlap;
+ }
+ }
+}
+
+void boxes_iou_bev_kernel(const int num_a, const float *boxes_a, const int num_b, const float *boxes_b, float *ans_iou) {
+ for (int a_idx = 0; a_idx < num_a; ++a_idx) {
+ const float *cur_box_a = boxes_a + a_idx * 5;
+ for (int b_idx = 0; b_idx < num_b; ++b_idx) {
+ const float *cur_box_b = boxes_b + b_idx * 5;
+ float cur_iou_bev = iou_bev(cur_box_a, cur_box_b);
+ ans_iou[a_idx * num_b + b_idx] = cur_iou_bev;
+ }
+ }
+}
+
+void nms_kernel(const int boxes_num, const float nms_overlap_thresh, const float *boxes, unsigned long long *mask) {
+ // mask layout follows original: for each row index cur_box_idx there are col_blocks entries
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+ // zero initialize mask
+ std::memset(mask, 0, sizeof(unsigned long long) * boxes_num * col_blocks);
+ for (int row_start = 0; row_start < DIVUP(boxes_num, THREADS_PER_BLOCK_NMS); ++row_start) {
+ for (int col_start = 0; col_start < DIVUP(boxes_num, THREADS_PER_BLOCK_NMS); ++col_start) {
+ int row_size = std::min(boxes_num - row_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+ int col_size = std::min(boxes_num - col_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+ // load block_boxes
+ std::vector block_boxes(col_size * 5);
+ for (int t = 0; t < col_size; ++t) {
+ int idx = THREADS_PER_BLOCK_NMS * col_start + t;
+ const float *src = boxes + idx * 5;
+ std::memcpy(&block_boxes[t * 5], src, sizeof(float) * 5);
+ }
+ for (int t = 0; t < row_size; ++t) {
+ int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + t;
+ const float *cur_box = boxes + cur_box_idx * 5;
+ unsigned long long u = 0ULL;
+ int start = 0;
+ if (row_start == col_start) start = t + 1;
+ for (int i = start; i < col_size; ++i) {
+ const float *other = &block_boxes[i * 5];
+ if (iou_bev(cur_box, other) > nms_overlap_thresh) {
+ u |= (1ULL << i);
+ }
+ }
+ mask[cur_box_idx * col_blocks + col_start] = u;
+ }
+ }
+ }
+}
+
+inline float iou_normal(const float *a, const float *b) {
+ float left = std::fmaxf(a[0], b[0]), right = std::fminf(a[2], b[2]);
+ float top = std::fmaxf(a[1], b[1]), bottom = std::fminf(a[3], b[3]);
+ float width = std::fmaxf(right - left, 0.f), height = std::fmaxf(bottom - top, 0.f);
+ float interS = width * height;
+ float Sa = (a[2] - a[0]) * (a[3] - a[1]);
+ float Sb = (b[2] - b[0]) * (b[3] - b[1]);
+ return interS / std::fmax(Sa + Sb - interS, EPS);
+}
+
+void nms_normal_kernel(const int boxes_num, const float nms_overlap_thresh, const float *boxes, unsigned long long *mask) {
+ const int col_blocks = DIVUP(boxes_num, THREADS_PER_BLOCK_NMS);
+ std::memset(mask, 0, sizeof(unsigned long long) * boxes_num * col_blocks);
+
+ for (int row_start = 0; row_start < DIVUP(boxes_num, THREADS_PER_BLOCK_NMS); ++row_start) {
+ for (int col_start = 0; col_start < DIVUP(boxes_num, THREADS_PER_BLOCK_NMS); ++col_start) {
+ int row_size = std::min(boxes_num - row_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+ int col_size = std::min(boxes_num - col_start * THREADS_PER_BLOCK_NMS, THREADS_PER_BLOCK_NMS);
+ std::vector block_boxes(col_size * 5);
+ for (int t = 0; t < col_size; ++t) {
+ int idx = THREADS_PER_BLOCK_NMS * col_start + t;
+ const float *src = boxes + idx * 5;
+ std::memcpy(&block_boxes[t * 5], src, sizeof(float) * 5);
+ }
+ for (int t = 0; t < row_size; ++t) {
+ int cur_box_idx = THREADS_PER_BLOCK_NMS * row_start + t;
+ const float *cur_box = boxes + cur_box_idx * 5;
+ unsigned long long u = 0ULL;
+ int start = 0;
+ if (row_start == col_start) start = t + 1;
+ for (int i = start; i < col_size; ++i) {
+ const float *other = &block_boxes[i * 5];
+ if (iou_normal(cur_box, other) > nms_overlap_thresh) {
+ u |= (1ULL << i);
+ }
+ }
+ mask[cur_box_idx * col_blocks + col_start] = u;
+ }
+ }
+ }
+}
+
+void boxesoverlapLauncher(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_overlap) {
+ boxes_overlap_kernel(num_a, boxes_a, num_b, boxes_b, ans_overlap);
+}
+
+void boxesioubevLauncher(const int num_a, const float *boxes_a,
+ const int num_b, const float *boxes_b,
+ float *ans_iou) {
+ boxes_iou_bev_kernel(num_a, boxes_a, num_b, boxes_b, ans_iou);
+}
+
+void nmsLauncher(const float *boxes, unsigned long long *mask,
+ int boxes_num, float nms_overlap_thresh) {
+ nms_kernel(boxes_num, nms_overlap_thresh, boxes, mask);
+}
+
+void nmsNormalLauncher(const float *boxes, unsigned long long *mask,
+ int boxes_num, float nms_overlap_thresh) {
+ nms_normal_kernel(boxes_num, nms_overlap_thresh, boxes, mask);
+}
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/iou3d_module.py b/notebooks/3D-point-pillars/pointpillars/ops/iou3d_module.py
new file mode 100644
index 00000000000..a4f376dd060
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/iou3d_module.py
@@ -0,0 +1,89 @@
+# This file is modified from https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/ops/iou3d/iou3d_utils.py
+
+import torch
+from pointpillars.ops.iou3d_op import boxes_overlap_bev_gpu, boxes_iou_bev_gpu, nms_gpu, nms_normal_gpu
+
+
+def boxes_overlap_bev(boxes_a, boxes_b):
+ """Calculate boxes Overlap in the bird view.
+
+ Args:
+ boxes_a (torch.Tensor): Input boxes a with shape (M, 5).
+ boxes_b (torch.Tensor): Input boxes b with shape (N, 5).
+
+ Returns:
+ ans_overlap (torch.Tensor): Overlap result with shape (M, N).
+ """
+ ans_overlap = boxes_a.new_zeros(
+ torch.Size((boxes_a.shape[0], boxes_b.shape[0])))
+
+ boxes_overlap_bev_gpu(boxes_a.contiguous(), boxes_b.contiguous(), ans_overlap)
+
+ return ans_overlap
+
+
+def boxes_iou_bev(boxes_a, boxes_b):
+ """Calculate boxes IoU in the bird view.
+
+ Args:
+ boxes_a (torch.Tensor): Input boxes a with shape (M, 5).
+ boxes_b (torch.Tensor): Input boxes b with shape (N, 5).
+
+ Returns:
+ ans_iou (torch.Tensor): IoU result with shape (M, N).
+ """
+ ans_iou = boxes_a.new_zeros(
+ torch.Size((boxes_a.shape[0], boxes_b.shape[0])))
+
+ boxes_iou_bev_gpu(boxes_a.contiguous(), boxes_b.contiguous(), ans_iou)
+
+ return ans_iou
+
+
+def nms_cuda(boxes, scores, thresh, pre_maxsize=None, post_max_size=None):
+ """Nms function with gpu implementation.
+
+ Args:
+ boxes (torch.Tensor): Input boxes with the shape of [N, 5]
+ ([x1, y1, x2, y2, ry]).
+ scores (torch.Tensor): Scores of boxes with the shape of [N].
+ thresh (int): Threshold.
+ pre_maxsize (int): Max size of boxes before nms. Default: None.
+ post_maxsize (int): Max size of boxes after nms. Default: None.
+
+ Returns:
+ torch.Tensor: Indexes after nms.
+ """
+ order = scores.sort(0, descending=True)[1]
+
+ if pre_maxsize is not None:
+ order = order[:pre_maxsize]
+ boxes = boxes[order].contiguous()
+
+ keep = torch.zeros(boxes.size(0), dtype=torch.long)
+ num_out = nms_gpu(boxes, keep, thresh, boxes.device.index)
+ keep = order[keep[:num_out].cuda(boxes.device)].contiguous()
+ if post_max_size is not None:
+ keep = keep[:post_max_size]
+ return keep
+
+
+def nms_normal_gpu(boxes, scores, thresh):
+ """Normal non maximum suppression on GPU.
+
+ Args:
+ boxes (torch.Tensor): Input boxes with shape (N, 5).
+ scores (torch.Tensor): Scores of predicted boxes with shape (N).
+ thresh (torch.Tensor): Threshold of non maximum suppression.
+
+ Returns:
+ torch.Tensor: Remaining indices with scores in descending order.
+ """
+ order = scores.sort(0, descending=True)[1]
+
+ boxes = boxes[order].contiguous()
+
+ keep = torch.zeros(boxes.size(0), dtype=torch.long)
+ num_out = nms_normal_gpu(boxes, keep, thresh,
+ boxes.device.index)
+ return order[keep[:num_out].cuda(boxes.device)].contiguous()
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/voxel_module.py b/notebooks/3D-point-pillars/pointpillars/ops/voxel_module.py
new file mode 100644
index 00000000000..fda4b046ba2
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/voxel_module.py
@@ -0,0 +1,133 @@
+# This file is modified from https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/ops/voxel/voxelize.py
+
+import torch
+import torch.nn as nn
+from pointpillars.ops.voxel_op import hard_voxelize
+
+
+class _Voxelization(torch.autograd.Function):
+
+ @staticmethod
+ def forward(ctx,
+ points,
+ voxel_size,
+ coors_range,
+ max_points=35,
+ max_voxels=20000,
+ deterministic=True):
+ """convert kitti points(N, >=3) to voxels.
+ Args:
+ points: [N, ndim] float tensor. points[:, :3] contain xyz points
+ and points[:, 3:] contain other information like reflectivity
+ voxel_size: [3] list/tuple or array, float. xyz, indicate voxel
+ size
+ coors_range: [6] list/tuple or array, float. indicate voxel
+ range. format: xyzxyz, minmax
+ max_points: int. indicate maximum points contained in a voxel. if
+ max_points=-1, it means using dynamic_voxelize
+ max_voxels: int. indicate maximum voxels this function create.
+ for second, 20000 is a good choice. Users should shuffle points
+ before call this function because max_voxels may drop points.
+ deterministic: bool. whether to invoke the non-deterministic
+ version of hard-voxelization implementations. non-deterministic
+ version is considerablly fast but is not deterministic. only
+ affects hard voxelization. default True. for more information
+ of this argument and the implementation insights, please refer
+ to the following links:
+ https://github.com/open-mmlab/mmdetection3d/issues/894
+ https://github.com/open-mmlab/mmdetection3d/pull/904
+ it is an experimental feature and we will appreciate it if
+ you could share with us the failing cases.
+ Returns:
+ voxels: [M, max_points, ndim] float tensor. only contain points
+ and returned when max_points != -1.
+ coordinates: [M, 3] int32 tensor, always returned.
+ num_points_per_voxel: [M] int32 tensor. Only returned when
+ max_points != -1.
+ """
+
+ voxels = points.new_zeros(
+ size=(max_voxels, max_points, points.size(1)))
+ coors = points.new_zeros(size=(max_voxels, 3), dtype=torch.int)
+ num_points_per_voxel = points.new_zeros(
+ size=(max_voxels, ), dtype=torch.int)
+ voxel_num = hard_voxelize(points, voxels, coors,
+ num_points_per_voxel, voxel_size,
+ coors_range, max_points, max_voxels, 3,
+ deterministic)
+ # select the valid voxels
+ voxels_out = voxels[:voxel_num]
+ coors_out = coors[:voxel_num].flip(-1) # (z, y, x) -> (x, y, z)
+ num_points_per_voxel_out = num_points_per_voxel[:voxel_num]
+ return voxels_out, coors_out, num_points_per_voxel_out
+
+
+class Voxelization(nn.Module):
+
+ def __init__(self,
+ voxel_size,
+ point_cloud_range,
+ max_num_points,
+ max_voxels,
+ deterministic=True):
+ super(Voxelization, self).__init__()
+ """
+ Args:
+ voxel_size (list): list [x, y, z] size of three dimension
+ point_cloud_range (list):
+ [x_min, y_min, z_min, x_max, y_max, z_max]
+ max_num_points (int): max number of points per voxel
+ max_voxels (tuple): max number of voxels in
+ (training, testing) time
+ deterministic: bool. whether to invoke the non-deterministic
+ version of hard-voxelization implementations. non-deterministic
+ version is considerablly fast but is not deterministic. only
+ affects hard voxelization. default True. for more information
+ of this argument and the implementation insights, please refer
+ to the following links:
+ https://github.com/open-mmlab/mmdetection3d/issues/894
+ https://github.com/open-mmlab/mmdetection3d/pull/904
+ it is an experimental feature and we will appreciate it if
+ you could share with us the failing cases.
+ """
+ self.voxel_size = voxel_size
+ self.point_cloud_range = point_cloud_range
+ self.max_num_points = max_num_points
+ self.max_voxels = max_voxels
+ self.deterministic = deterministic
+
+ point_cloud_range = torch.tensor(
+ point_cloud_range, dtype=torch.float32)
+
+ voxel_size = torch.tensor(voxel_size, dtype=torch.float32)
+ grid_size = (point_cloud_range[3:] -
+ point_cloud_range[:3]) / voxel_size
+ grid_size = torch.round(grid_size).long()
+ input_feat_shape = grid_size[:2]
+ self.grid_size = grid_size
+ # the origin shape is as [x-len, y-len, z-len]
+ # [w, h, d] -> [d, h, w]
+ self.pcd_shape = [*input_feat_shape, 1][::-1]
+
+ def forward(self, input):
+ """
+ input: shape=(N, c)
+ """
+ if self.training:
+ max_voxels = self.max_voxels[0]
+ else:
+ max_voxels = self.max_voxels[1]
+
+ return _Voxelization.apply(input, self.voxel_size, self.point_cloud_range,
+ self.max_num_points, max_voxels,
+ self.deterministic)
+
+ def __repr__(self):
+ tmpstr = self.__class__.__name__ + '('
+ tmpstr += 'voxel_size=' + str(self.voxel_size)
+ tmpstr += ', point_cloud_range=' + str(self.point_cloud_range)
+ tmpstr += ', max_num_points=' + str(self.max_num_points)
+ tmpstr += ', max_voxels=' + str(self.max_voxels)
+ tmpstr += ', deterministic=' + str(self.deterministic)
+ tmpstr += ')'
+ return tmpstr
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.cpp b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.cpp
new file mode 100644
index 00000000000..2fc1155476e
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.cpp
@@ -0,0 +1,10 @@
+#include
+#include "voxelization.h"
+
+namespace voxelization {
+
+PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {
+ m.def("hard_voxelize", &hard_voxelize, "hard voxelize");
+}
+
+} // namespace voxelization
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.h b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.h
new file mode 100644
index 00000000000..116bead491d
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization.h
@@ -0,0 +1,69 @@
+#pragma once
+#include
+
+typedef enum { SUM = 0, MEAN = 1, MAX = 2 } reduce_t;
+
+namespace voxelization {
+
+int hard_voxelize_cpu(const at::Tensor &points, at::Tensor &voxels,
+ at::Tensor &coors, at::Tensor &num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3);
+
+#ifdef WITH_CUDA
+int hard_voxelize_gpu(const at::Tensor &points, at::Tensor &voxels,
+ at::Tensor &coors, at::Tensor &num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3);
+
+int nondisterministic_hard_voxelize_gpu(const at::Tensor &points, at::Tensor &voxels,
+ at::Tensor &coors, at::Tensor &num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3);
+#endif
+
+// Interface for Python
+inline int hard_voxelize(const at::Tensor &points, at::Tensor &voxels,
+ at::Tensor &coors, at::Tensor &num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3, const bool deterministic = true) {
+ if (points.device().is_cuda()) {
+#ifdef WITH_CUDA
+ if (deterministic) {
+ return hard_voxelize_gpu(points, voxels, coors, num_points_per_voxel,
+ voxel_size, coors_range, max_points, max_voxels,
+ NDim);
+ }
+ return nondisterministic_hard_voxelize_gpu(points, voxels, coors, num_points_per_voxel,
+ voxel_size, coors_range, max_points, max_voxels,
+ NDim);
+#else
+ AT_ERROR("Not compiled with GPU support");
+#endif
+ }
+ return hard_voxelize_cpu(points, voxels, coors, num_points_per_voxel,
+ voxel_size, coors_range, max_points, max_voxels,
+ NDim);
+}
+
+
+inline reduce_t convert_reduce_type(const std::string &reduce_type) {
+ if (reduce_type == "max")
+ return reduce_t::MAX;
+ else if (reduce_type == "sum")
+ return reduce_t::SUM;
+ else if (reduce_type == "mean")
+ return reduce_t::MEAN;
+ else TORCH_CHECK(false, "do not support reduce type " + reduce_type)
+ return reduce_t::SUM;
+}
+
+} // namespace voxelization
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cpu.cpp b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cpu.cpp
new file mode 100644
index 00000000000..26a247faddf
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cpu.cpp
@@ -0,0 +1,173 @@
+#include
+#include
+
+namespace {
+
+template
+void dynamic_voxelize_kernel(const torch::TensorAccessor points,
+ torch::TensorAccessor coors,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const std::vector grid_size,
+ const int num_points, const int num_features,
+ const int NDim) {
+ const int ndim_minus_1 = NDim - 1;
+ bool failed = false;
+ // int coor[NDim];
+ int* coor = new int[NDim]();
+ int c;
+
+ for (int i = 0; i < num_points; ++i) {
+ failed = false;
+ for (int j = 0; j < NDim; ++j) {
+ c = floor((points[i][j] - coors_range[j]) / voxel_size[j]);
+ // necessary to rm points out of range
+ if ((c < 0 || c >= grid_size[j])) {
+ failed = true;
+ break;
+ }
+ coor[ndim_minus_1 - j] = c;
+ }
+
+ for (int k = 0; k < NDim; ++k) {
+ if (failed)
+ coors[i][k] = -1;
+ else
+ coors[i][k] = coor[k];
+ }
+ }
+
+ delete[] coor;
+ return;
+}
+
+template
+void hard_voxelize_kernel(const torch::TensorAccessor points,
+ torch::TensorAccessor voxels,
+ torch::TensorAccessor coors,
+ torch::TensorAccessor num_points_per_voxel,
+ torch::TensorAccessor coor_to_voxelidx,
+ int& voxel_num, const std::vector voxel_size,
+ const std::vector coors_range,
+ const std::vector grid_size,
+ const int max_points, const int max_voxels,
+ const int num_points, const int num_features,
+ const int NDim) {
+ // declare a temp coors
+ at::Tensor temp_coors = at::zeros(
+ {num_points, NDim}, at::TensorOptions().dtype(at::kInt).device(at::kCPU));
+
+ // First use dynamic voxelization to get coors,
+ // then check max points/voxels constraints
+ dynamic_voxelize_kernel(points, temp_coors.accessor(),
+ voxel_size, coors_range, grid_size,
+ num_points, num_features, NDim);
+
+ int voxelidx, num;
+ auto coor = temp_coors.accessor();
+
+ for (int i = 0; i < num_points; ++i) {
+ // T_int* coor = temp_coors.data_ptr() + i * NDim;
+
+ if (coor[i][0] == -1) continue;
+
+ voxelidx = coor_to_voxelidx[coor[i][0]][coor[i][1]][coor[i][2]];
+
+ // record voxel
+ if (voxelidx == -1) {
+ voxelidx = voxel_num;
+ if (max_voxels != -1 && voxel_num >= max_voxels) continue;
+ voxel_num += 1;
+
+ coor_to_voxelidx[coor[i][0]][coor[i][1]][coor[i][2]] = voxelidx;
+
+ for (int k = 0; k < NDim; ++k) {
+ coors[voxelidx][k] = coor[i][k];
+ }
+ }
+
+ // put points into voxel
+ num = num_points_per_voxel[voxelidx];
+ if (max_points == -1 || num < max_points) {
+ for (int k = 0; k < num_features; ++k) {
+ voxels[voxelidx][num][k] = points[i][k];
+ }
+ num_points_per_voxel[voxelidx] += 1;
+ }
+ }
+
+ return;
+}
+
+} // namespace
+
+namespace voxelization {
+
+int hard_voxelize_cpu(const at::Tensor& points, at::Tensor& voxels,
+ at::Tensor& coors, at::Tensor& num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3) {
+
+
+ // check device
+ AT_ASSERTM(points.device().is_cpu(), "points must be a CPU tensor");
+
+ std::vector grid_size(NDim);
+ const int num_points = points.size(0);
+ const int num_features = points.size(1);
+
+ for (int i = 0; i < NDim; ++i) {
+ grid_size[i] =
+ round((coors_range[NDim + i] - coors_range[i]) / voxel_size[i]);
+ }
+
+ // coors, num_points_per_voxel, coor_to_voxelidx are int Tensor
+ // printf("cpu coor_to_voxelidx size: [%d, %d, %d]\n", grid_size[2],
+ // grid_size[1], grid_size[0]);
+ at::Tensor coor_to_voxelidx =
+ -at::ones({grid_size[2], grid_size[1], grid_size[0]}, coors.options());
+
+ int voxel_num = 0;
+ AT_DISPATCH_FLOATING_TYPES_AND_HALF(
+ points.scalar_type(), "hard_voxelize_forward", [&] {
+ hard_voxelize_kernel(
+ points.accessor(), voxels.accessor(),
+ coors.accessor(), num_points_per_voxel.accessor(),
+ coor_to_voxelidx.accessor(), voxel_num, voxel_size,
+ coors_range, grid_size, max_points, max_voxels, num_points,
+ num_features, NDim);
+ });
+
+ return voxel_num;
+}
+
+void dynamic_voxelize_cpu(const at::Tensor& points, at::Tensor& coors,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int NDim = 3) {
+ // check device
+ AT_ASSERTM(points.device().is_cpu(), "points must be a CPU tensor");
+
+ std::vector grid_size(NDim);
+ const int num_points = points.size(0);
+ const int num_features = points.size(1);
+
+ for (int i = 0; i < NDim; ++i) {
+ grid_size[i] =
+ round((coors_range[NDim + i] - coors_range[i]) / voxel_size[i]);
+ }
+
+ // coors, num_points_per_voxel, coor_to_voxelidx are int Tensor
+ AT_DISPATCH_FLOATING_TYPES_AND_HALF(
+ points.scalar_type(), "hard_voxelize_forward", [&] {
+ dynamic_voxelize_kernel(
+ points.accessor(), coors.accessor(),
+ voxel_size, coors_range, grid_size, num_points, num_features, NDim);
+ });
+
+ return;
+}
+
+} // namespace voxelization
diff --git a/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cuda.cu b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cuda.cu
new file mode 100644
index 00000000000..b4edcf3b147
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/ops/voxelization/voxelization_cuda.cu
@@ -0,0 +1,530 @@
+#include
+#include
+#include
+#include
+
+#include
+
+#define CHECK_CUDA(x) \
+ TORCH_CHECK(x.device().is_cuda(), #x " must be a CUDA tensor")
+#define CHECK_CONTIGUOUS(x) \
+ TORCH_CHECK(x.is_contiguous(), #x " must be contiguous")
+#define CHECK_INPUT(x) \
+ CHECK_CUDA(x); \
+ CHECK_CONTIGUOUS(x)
+
+namespace {
+int const threadsPerBlock = sizeof(unsigned long long) * 8;
+}
+
+#define CUDA_1D_KERNEL_LOOP(i, n) \
+ for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < n; \
+ i += blockDim.x * gridDim.x)
+
+template
+__global__ void dynamic_voxelize_kernel(
+ const T* points, T_int* coors, const float voxel_x, const float voxel_y,
+ const float voxel_z, const float coors_x_min, const float coors_y_min,
+ const float coors_z_min, const float coors_x_max, const float coors_y_max,
+ const float coors_z_max, const int grid_x, const int grid_y,
+ const int grid_z, const int num_points, const int num_features,
+ const int NDim) {
+ // const int index = blockIdx.x * threadsPerBlock + threadIdx.x;
+ CUDA_1D_KERNEL_LOOP(index, num_points) {
+ // To save some computation
+ auto points_offset = points + index * num_features;
+ auto coors_offset = coors + index * NDim;
+ int c_x = floor((points_offset[0] - coors_x_min) / voxel_x);
+ if (c_x < 0 || c_x >= grid_x) {
+ coors_offset[0] = -1;
+ return;
+ }
+
+ int c_y = floor((points_offset[1] - coors_y_min) / voxel_y);
+ if (c_y < 0 || c_y >= grid_y) {
+ coors_offset[0] = -1;
+ coors_offset[1] = -1;
+ return;
+ }
+
+ int c_z = floor((points_offset[2] - coors_z_min) / voxel_z);
+ if (c_z < 0 || c_z >= grid_z) {
+ coors_offset[0] = -1;
+ coors_offset[1] = -1;
+ coors_offset[2] = -1;
+ } else {
+ coors_offset[0] = c_z;
+ coors_offset[1] = c_y;
+ coors_offset[2] = c_x;
+ }
+ }
+}
+
+template
+__global__ void assign_point_to_voxel(const int nthreads, const T* points,
+ T_int* point_to_voxelidx,
+ T_int* coor_to_voxelidx, T* voxels,
+ const int max_points,
+ const int num_features,
+ const int num_points, const int NDim) {
+ CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {
+ // const int index = blockIdx.x * threadsPerBlock + threadIdx.x;
+ int index = thread_idx / num_features;
+
+ int num = point_to_voxelidx[index];
+ int voxelidx = coor_to_voxelidx[index];
+ if (num > -1 && voxelidx > -1) {
+ auto voxels_offset =
+ voxels + voxelidx * max_points * num_features + num * num_features;
+
+ int k = thread_idx % num_features;
+ voxels_offset[k] = points[thread_idx];
+ }
+ }
+}
+
+template
+__global__ void assign_voxel_coors(const int nthreads, T_int* coor,
+ T_int* point_to_voxelidx,
+ T_int* coor_to_voxelidx, T_int* voxel_coors,
+ const int num_points, const int NDim) {
+ CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {
+ // const int index = blockIdx.x * threadsPerBlock + threadIdx.x;
+ // if (index >= num_points) return;
+ int index = thread_idx / NDim;
+ int num = point_to_voxelidx[index];
+ int voxelidx = coor_to_voxelidx[index];
+ if (num == 0 && voxelidx > -1) {
+ auto coors_offset = voxel_coors + voxelidx * NDim;
+ int k = thread_idx % NDim;
+ coors_offset[k] = coor[thread_idx];
+ }
+ }
+}
+
+template
+__global__ void point_to_voxelidx_kernel(const T_int* coor,
+ T_int* point_to_voxelidx,
+ T_int* point_to_pointidx,
+ const int max_points,
+ const int max_voxels,
+ const int num_points, const int NDim) {
+ CUDA_1D_KERNEL_LOOP(index, num_points) {
+ auto coor_offset = coor + index * NDim;
+ // skip invalid points
+ if ((index >= num_points) || (coor_offset[0] == -1)) return;
+
+ int num = 0;
+ int coor_x = coor_offset[0];
+ int coor_y = coor_offset[1];
+ int coor_z = coor_offset[2];
+ // only calculate the coors before this coor[index]
+ for (int i = 0; i < index; ++i) {
+ auto prev_coor = coor + i * NDim;
+ if (prev_coor[0] == -1) continue;
+
+ // Find all previous points that have the same coors
+ // if find the same coor, record it
+ if ((prev_coor[0] == coor_x) && (prev_coor[1] == coor_y) &&
+ (prev_coor[2] == coor_z)) {
+ num++;
+ if (num == 1) {
+ // point to the same coor that first show up
+ point_to_pointidx[index] = i;
+ } else if (num >= max_points) {
+ // out of boundary
+ return;
+ }
+ }
+ }
+ if (num == 0) {
+ point_to_pointidx[index] = index;
+ }
+ if (num < max_points) {
+ point_to_voxelidx[index] = num;
+ }
+ }
+}
+
+template
+__global__ void determin_voxel_num(
+ // const T_int* coor,
+ T_int* num_points_per_voxel, T_int* point_to_voxelidx,
+ T_int* point_to_pointidx, T_int* coor_to_voxelidx, T_int* voxel_num,
+ const int max_points, const int max_voxels, const int num_points) {
+ // only calculate the coors before this coor[index]
+ for (int i = 0; i < num_points; ++i) {
+ // if (coor[i][0] == -1)
+ // continue;
+ int point_pos_in_voxel = point_to_voxelidx[i];
+ // record voxel
+ if (point_pos_in_voxel == -1) {
+ // out of max_points or invalid point
+ continue;
+ } else if (point_pos_in_voxel == 0) {
+ // record new voxel
+ int voxelidx = voxel_num[0];
+ if (voxel_num[0] >= max_voxels) continue;
+ voxel_num[0] += 1;
+ coor_to_voxelidx[i] = voxelidx;
+ num_points_per_voxel[voxelidx] = 1;
+ } else {
+ int point_idx = point_to_pointidx[i];
+ int voxelidx = coor_to_voxelidx[point_idx];
+ if (voxelidx != -1) {
+ coor_to_voxelidx[i] = voxelidx;
+ num_points_per_voxel[voxelidx] += 1;
+ }
+ }
+ }
+}
+
+__global__ void nondisterministic_get_assign_pos(
+ const int nthreads, const int32_t *coors_map, int32_t *pts_id,
+ int32_t *coors_count, int32_t *reduce_count, int32_t *coors_order) {
+ CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {
+ int coors_idx = coors_map[thread_idx];
+ if (coors_idx > -1) {
+ int32_t coors_pts_pos = atomicAdd(&reduce_count[coors_idx], 1);
+ pts_id[thread_idx] = coors_pts_pos;
+ if (coors_pts_pos == 0) {
+ coors_order[coors_idx] = atomicAdd(coors_count, 1);
+ }
+ }
+ }
+}
+
+template
+__global__ void nondisterministic_assign_point_voxel(
+ const int nthreads, const T *points, const int32_t *coors_map,
+ const int32_t *pts_id, const int32_t *coors_in,
+ const int32_t *reduce_count, const int32_t *coors_order,
+ T *voxels, int32_t *coors, int32_t *pts_count, const int max_voxels,
+ const int max_points, const int num_features, const int NDim) {
+ CUDA_1D_KERNEL_LOOP(thread_idx, nthreads) {
+ int coors_idx = coors_map[thread_idx];
+ int coors_pts_pos = pts_id[thread_idx];
+ if (coors_idx > -1) {
+ int coors_pos = coors_order[coors_idx];
+ if (coors_pos < max_voxels && coors_pts_pos < max_points) {
+ auto voxels_offset =
+ voxels + (coors_pos * max_points + coors_pts_pos) * num_features;
+ auto points_offset = points + thread_idx * num_features;
+ for (int k = 0; k < num_features; k++) {
+ voxels_offset[k] = points_offset[k];
+ }
+ if (coors_pts_pos == 0) {
+ pts_count[coors_pos] = min(reduce_count[coors_idx], max_points);
+ auto coors_offset = coors + coors_pos * NDim;
+ auto coors_in_offset = coors_in + coors_idx * NDim;
+ for (int k = 0; k < NDim; k++) {
+ coors_offset[k] = coors_in_offset[k];
+ }
+ }
+ }
+ }
+ }
+}
+
+namespace voxelization {
+
+int hard_voxelize_gpu(const at::Tensor& points, at::Tensor& voxels,
+ at::Tensor& coors, at::Tensor& num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3) {
+ // current version tooks about 0.04s for one frame on cpu
+ // check device
+ CHECK_INPUT(points);
+
+ at::cuda::CUDAGuard device_guard(points.device());
+
+ const int num_points = points.size(0);
+ const int num_features = points.size(1);
+
+ const float voxel_x = voxel_size[0];
+ const float voxel_y = voxel_size[1];
+ const float voxel_z = voxel_size[2];
+ const float coors_x_min = coors_range[0];
+ const float coors_y_min = coors_range[1];
+ const float coors_z_min = coors_range[2];
+ const float coors_x_max = coors_range[3];
+ const float coors_y_max = coors_range[4];
+ const float coors_z_max = coors_range[5];
+
+ const int grid_x = round((coors_x_max - coors_x_min) / voxel_x);
+ const int grid_y = round((coors_y_max - coors_y_min) / voxel_y);
+ const int grid_z = round((coors_z_max - coors_z_min) / voxel_z);
+
+ // map points to voxel coors
+ at::Tensor temp_coors =
+ at::zeros({num_points, NDim}, points.options().dtype(at::kInt));
+
+ dim3 grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));
+ dim3 block(512);
+
+ // 1. link point to corresponding voxel coors
+ AT_DISPATCH_ALL_TYPES(
+ points.scalar_type(), "hard_voxelize_kernel", ([&] {
+ dynamic_voxelize_kernel
+ <<>>(
+ points.contiguous().data_ptr(),
+ temp_coors.contiguous().data_ptr(), voxel_x, voxel_y,
+ voxel_z, coors_x_min, coors_y_min, coors_z_min, coors_x_max,
+ coors_y_max, coors_z_max, grid_x, grid_y, grid_z, num_points,
+ num_features, NDim);
+ }));
+ cudaDeviceSynchronize();
+ AT_CUDA_CHECK(cudaGetLastError());
+
+ // 2. map point to the idx of the corresponding voxel, find duplicate coor
+ // create some temporary variables
+ auto point_to_pointidx = -at::ones(
+ {
+ num_points,
+ },
+ points.options().dtype(at::kInt));
+ auto point_to_voxelidx = -at::ones(
+ {
+ num_points,
+ },
+ points.options().dtype(at::kInt));
+
+ dim3 map_grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));
+ dim3 map_block(512);
+ AT_DISPATCH_ALL_TYPES(
+ temp_coors.scalar_type(), "determin_duplicate", ([&] {
+ point_to_voxelidx_kernel
+ <<>>(
+ temp_coors.contiguous().data_ptr(),
+ point_to_voxelidx.contiguous().data_ptr(),
+ point_to_pointidx.contiguous().data_ptr(), max_points,
+ max_voxels, num_points, NDim);
+ }));
+ cudaDeviceSynchronize();
+ AT_CUDA_CHECK(cudaGetLastError());
+
+ // 3. determin voxel num and voxel's coor index
+ // make the logic in the CUDA device could accelerate about 10 times
+ auto coor_to_voxelidx = -at::ones(
+ {
+ num_points,
+ },
+ points.options().dtype(at::kInt));
+ auto voxel_num = at::zeros(
+ {
+ 1,
+ },
+ points.options().dtype(at::kInt)); // must be zero from the begining
+
+ AT_DISPATCH_ALL_TYPES(
+ temp_coors.scalar_type(), "determin_duplicate", ([&] {
+ determin_voxel_num<<<1, 1, 0, at::cuda::getCurrentCUDAStream()>>>(
+ num_points_per_voxel.contiguous().data_ptr(),
+ point_to_voxelidx.contiguous().data_ptr(),
+ point_to_pointidx.contiguous().data_ptr(),
+ coor_to_voxelidx.contiguous().data_ptr(),
+ voxel_num.contiguous().data_ptr(), max_points, max_voxels,
+ num_points);
+ }));
+ cudaDeviceSynchronize();
+ AT_CUDA_CHECK(cudaGetLastError());
+
+ // 4. copy point features to voxels
+ // Step 4 & 5 could be parallel
+ auto pts_output_size = num_points * num_features;
+ dim3 cp_grid(std::min(at::cuda::ATenCeilDiv(pts_output_size, 512), 4096));
+ dim3 cp_block(512);
+ AT_DISPATCH_ALL_TYPES(
+ points.scalar_type(), "assign_point_to_voxel", ([&] {
+ assign_point_to_voxel
+ <<>>(
+ pts_output_size, points.contiguous().data_ptr(),
+ point_to_voxelidx.contiguous().data_ptr(),
+ coor_to_voxelidx.contiguous().data_ptr(),
+ voxels.contiguous().data_ptr(), max_points, num_features,
+ num_points, NDim);
+ }));
+ // cudaDeviceSynchronize();
+ // AT_CUDA_CHECK(cudaGetLastError());
+
+ // 5. copy coors of each voxels
+ auto coors_output_size = num_points * NDim;
+ dim3 coors_cp_grid(
+ std::min(at::cuda::ATenCeilDiv(coors_output_size, 512), 4096));
+ dim3 coors_cp_block(512);
+ AT_DISPATCH_ALL_TYPES(
+ points.scalar_type(), "assign_point_to_voxel", ([&] {
+ assign_voxel_coors<<>>(
+ coors_output_size, temp_coors.contiguous().data_ptr(),
+ point_to_voxelidx.contiguous().data_ptr(),
+ coor_to_voxelidx.contiguous().data_ptr(),
+ coors.contiguous().data_ptr(), num_points, NDim);
+ }));
+ cudaDeviceSynchronize();
+ AT_CUDA_CHECK(cudaGetLastError());
+
+ auto voxel_num_cpu = voxel_num.to(at::kCPU);
+ int voxel_num_int = voxel_num_cpu.data_ptr()[0];
+
+ return voxel_num_int;
+}
+
+int nondisterministic_hard_voxelize_gpu(
+ const at::Tensor &points, at::Tensor &voxels,
+ at::Tensor &coors, at::Tensor &num_points_per_voxel,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int max_points, const int max_voxels,
+ const int NDim = 3) {
+
+ CHECK_INPUT(points);
+
+ at::cuda::CUDAGuard device_guard(points.device());
+
+ const int num_points = points.size(0);
+ const int num_features = points.size(1);
+
+ if (num_points == 0)
+ return 0;
+
+ const float voxel_x = voxel_size[0];
+ const float voxel_y = voxel_size[1];
+ const float voxel_z = voxel_size[2];
+ const float coors_x_min = coors_range[0];
+ const float coors_y_min = coors_range[1];
+ const float coors_z_min = coors_range[2];
+ const float coors_x_max = coors_range[3];
+ const float coors_y_max = coors_range[4];
+ const float coors_z_max = coors_range[5];
+
+ const int grid_x = round((coors_x_max - coors_x_min) / voxel_x);
+ const int grid_y = round((coors_y_max - coors_y_min) / voxel_y);
+ const int grid_z = round((coors_z_max - coors_z_min) / voxel_z);
+
+ // map points to voxel coors
+ at::Tensor temp_coors =
+ at::zeros({num_points, NDim}, points.options().dtype(torch::kInt32));
+
+ dim3 grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));
+ dim3 block(512);
+
+ // 1. link point to corresponding voxel coors
+ AT_DISPATCH_ALL_TYPES(
+ points.scalar_type(), "hard_voxelize_kernel", ([&] {
+ dynamic_voxelize_kernel
+ <<>>(
+ points.contiguous().data_ptr(),
+ temp_coors.contiguous().data_ptr(), voxel_x, voxel_y,
+ voxel_z, coors_x_min, coors_y_min, coors_z_min, coors_x_max,
+ coors_y_max, coors_z_max, grid_x, grid_y, grid_z, num_points,
+ num_features, NDim);
+ }));
+
+ at::Tensor coors_map;
+ at::Tensor coors_count;
+ at::Tensor coors_order;
+ at::Tensor reduce_count;
+ at::Tensor pts_id;
+
+ auto coors_clean = temp_coors.masked_fill(temp_coors.lt(0).any(-1, true), -1);
+
+ std::tie(temp_coors, coors_map, reduce_count) =
+ at::unique_dim(coors_clean, 0, true, true, false);
+
+ if (temp_coors.index({0, 0}).lt(0).item()) {
+ // the first element of temp_coors is (-1,-1,-1) and should be removed
+ temp_coors = temp_coors.slice(0, 1);
+ coors_map = coors_map - 1;
+ }
+
+ int num_coors = temp_coors.size(0);
+ temp_coors = temp_coors.to(torch::kInt32);
+ coors_map = coors_map.to(torch::kInt32);
+
+ coors_count = coors_map.new_zeros(1);
+ coors_order = coors_map.new_empty(num_coors);
+ reduce_count = coors_map.new_zeros(num_coors);
+ pts_id = coors_map.new_zeros(num_points);
+
+ dim3 cp_grid(std::min(at::cuda::ATenCeilDiv(num_points, 512), 4096));
+ dim3 cp_block(512);
+ AT_DISPATCH_ALL_TYPES(points.scalar_type(), "get_assign_pos", ([&] {
+ nondisterministic_get_assign_pos<<>>(
+ num_points,
+ coors_map.contiguous().data_ptr(),
+ pts_id.contiguous().data_ptr(),
+ coors_count.contiguous().data_ptr(),
+ reduce_count.contiguous().data_ptr(),
+ coors_order.contiguous().data_ptr());
+ }));
+
+ AT_DISPATCH_ALL_TYPES(
+ points.scalar_type(), "assign_point_to_voxel", ([&] {
+ nondisterministic_assign_point_voxel
+ <<>>(
+ num_points, points.contiguous().data_ptr(),
+ coors_map.contiguous().data_ptr(),
+ pts_id.contiguous().data_ptr(),
+ temp_coors.contiguous().data_ptr(),
+ reduce_count.contiguous().data_ptr(),
+ coors_order.contiguous().data_ptr(),
+ voxels.contiguous().data_ptr(),
+ coors.contiguous().data_ptr(),
+ num_points_per_voxel.contiguous().data_ptr(),
+ max_voxels, max_points,
+ num_features, NDim);
+ }));
+ AT_CUDA_CHECK(cudaGetLastError());
+ return max_voxels < num_coors ? max_voxels : num_coors;
+}
+
+void dynamic_voxelize_gpu(const at::Tensor& points, at::Tensor& coors,
+ const std::vector voxel_size,
+ const std::vector coors_range,
+ const int NDim = 3) {
+ // current version tooks about 0.04s for one frame on cpu
+ // check device
+ CHECK_INPUT(points);
+
+ at::cuda::CUDAGuard device_guard(points.device());
+
+ const int num_points = points.size(0);
+ const int num_features = points.size(1);
+
+ const float voxel_x = voxel_size[0];
+ const float voxel_y = voxel_size[1];
+ const float voxel_z = voxel_size[2];
+ const float coors_x_min = coors_range[0];
+ const float coors_y_min = coors_range[1];
+ const float coors_z_min = coors_range[2];
+ const float coors_x_max = coors_range[3];
+ const float coors_y_max = coors_range[4];
+ const float coors_z_max = coors_range[5];
+
+ const int grid_x = round((coors_x_max - coors_x_min) / voxel_x);
+ const int grid_y = round((coors_y_max - coors_y_min) / voxel_y);
+ const int grid_z = round((coors_z_max - coors_z_min) / voxel_z);
+
+ const int col_blocks = at::cuda::ATenCeilDiv(num_points, threadsPerBlock);
+ dim3 blocks(col_blocks);
+ dim3 threads(threadsPerBlock);
+ cudaStream_t stream = at::cuda::getCurrentCUDAStream();
+
+ AT_DISPATCH_ALL_TYPES(points.scalar_type(), "dynamic_voxelize_kernel", [&] {
+ dynamic_voxelize_kernel<<>>(
+ points.contiguous().data_ptr(),
+ coors.contiguous().data_ptr(), voxel_x, voxel_y, voxel_z,
+ coors_x_min, coors_y_min, coors_z_min, coors_x_max, coors_y_max,
+ coors_z_max, grid_x, grid_y, grid_z, num_points, num_features, NDim);
+ });
+ cudaDeviceSynchronize();
+ AT_CUDA_CHECK(cudaGetLastError());
+
+ return;
+}
+
+} // namespace voxelization
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/__init__.py b/notebooks/3D-point-pillars/pointpillars/utils/__init__.py
new file mode 100644
index 00000000000..aeb73a790a3
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/__init__.py
@@ -0,0 +1,9 @@
+from .io import read_pickle, write_pickle, read_points, write_points, read_calib, \
+ read_label, write_label
+from .process import bbox_camera2lidar, bbox3d2bevcorners, box_collision_test, \
+ remove_pts_in_bboxes, limit_period, bbox3d2corners, points_lidar2image, \
+ keep_bbox_from_image_range, keep_bbox_from_lidar_range, \
+ points_camera2lidar, setup_seed, remove_outside_points, points_in_bboxes_v2, \
+ get_points_num_in_bbox, iou2d_nearest, iou2d, iou3d, iou3d_camera, iou_bev, \
+ bbox3d2corners_camera, points_camera2image
+from .vis_o3d import vis_pc, vis_img_3d
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/convert_bin_to_pcd.py b/notebooks/3D-point-pillars/pointpillars/utils/convert_bin_to_pcd.py
new file mode 100644
index 00000000000..005edc37761
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/convert_bin_to_pcd.py
@@ -0,0 +1,72 @@
+#!/usr/bin/env python3
+"""Convert a single KITTI .bin file to .pcd (saved alongside .bin) and optionally verify.
+
+Usage:
+ python scripts/convert_bin_to_pcd.py path/to/file.bin
+ python scripts/convert_bin_to_pcd.py path/to/file.bin --verify
+ python scripts/convert_bin_to_pcd.py path/to/file.bin --overwrite --verify
+
+Example:
+ python pointpillars/utils/convert_bin_to_pcd.py pointpillars/dataset/demo_data/val/000134.bin --overwrite --verify
+"""
+import argparse
+import os
+import sys
+
+# Ensure repo root is on sys.path so `pointpillars` package can be imported
+REPO_ROOT = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
+if REPO_ROOT not in sys.path:
+ sys.path.insert(0, REPO_ROOT)
+
+from pointpillars.dataset.kitti_open3d.utils import (
+ convert_bin_to_pcd,
+ compare_bin_pcd_file,
+)
+
+def main():
+ parser = argparse.ArgumentParser(
+ description="Convert a single KITTI .bin file to .pcd (saved alongside .bin)")
+ parser.add_argument("bin_path", help="Path to .bin file")
+ parser.add_argument("--overwrite", action="store_true",
+ help="Overwrite existing .pcd file")
+ parser.add_argument("--verify", action="store_true",
+ help="After conversion, read back and compare with original .bin")
+ args = parser.parse_args()
+
+ bin_path = args.bin_path
+ if not os.path.isfile(bin_path):
+ print(f"File not found: {bin_path}", file=sys.stderr)
+ sys.exit(1)
+
+ if not bin_path.lower().endswith('.bin'):
+ print(f"Expected .bin file, got: {bin_path}", file=sys.stderr)
+ sys.exit(1)
+
+ # Derive output path (same location, .pcd extension)
+ pcd_path = os.path.splitext(bin_path)[0] + '.pcd'
+
+ if os.path.exists(pcd_path) and not args.overwrite:
+ print(f"PCD already exists (use --overwrite to replace): {pcd_path}")
+ sys.exit(0)
+
+ # Convert
+ print(f"Converting: {bin_path} -> {pcd_path}")
+ try:
+ convert_bin_to_pcd(bin_path, pcd_path)
+ print("✓ Conversion complete")
+ except Exception as e:
+ print(f"✗ Conversion failed: {e}", file=sys.stderr)
+ sys.exit(1)
+
+ # Optionally verify
+ if args.verify:
+ print("\nVerifying...")
+ if compare_bin_pcd_file(bin_path, pcd_path):
+ print("✓ Verification passed")
+ else:
+ print("✗ Verification failed", file=sys.stderr)
+ sys.exit(1)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/convert_kitti_split_to_pcd.py b/notebooks/3D-point-pillars/pointpillars/utils/convert_kitti_split_to_pcd.py
new file mode 100644
index 00000000000..ad3e27dd110
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/convert_kitti_split_to_pcd.py
@@ -0,0 +1,119 @@
+#!/usr/bin/env python3
+"""Convert KITTI split pointclouds referenced in kitti_infos_{split}.pkl to binary PCD.
+
+Usage:
+ python scripts/convert_kitti_split_to_pcd.py --data-root /path/to/dataset --split val
+
+Example:
+ python pointpillars/utils/convert_kitti_split_to_pcd.py --data-root Datasets --split val --overwrite --verify
+
+The script reads Datasets/kitti_infos_{split}.pkl and converts each referenced
+velodyne .bin file (x,y,z,intensity float32) to a binary .pcd with ALL 4 fields
+preserved (x, y, z, intensity). The PCD format is PCL-compatible.
+
+To read the PCD files back as Nx4 arrays, use read_kitti_pcd() from this module.
+"""
+import argparse
+import os
+import pickle
+import sys
+
+REPO_ROOT = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
+if REPO_ROOT not in sys.path:
+ sys.path.insert(0, REPO_ROOT)
+
+from pointpillars.dataset.kitti_open3d.utils import (
+ convert_bin_to_pcd,
+ compare_bin_pcd_file,
+)
+
+
+def main():
+ parser = argparse.ArgumentParser(description='Convert KITTI split to PCD')
+ parser.add_argument('--data-root', default='Datasets', help='KITTI-like data root')
+ parser.add_argument('--split', default='val', choices=['train','val','trainval','test'])
+ parser.add_argument('--out-dir', default=None, help='Output directory for pcd files (default: /pcd_ or derived from pts-prefix)')
+ parser.add_argument('--pts-prefix', default='velodyne_reduced', help='Pointcloud folder prefix to use (mirrors Kitti default)')
+ parser.add_argument('--max', type=int, default=0, help='Max number of files to convert (0=all)')
+ parser.add_argument('--overwrite', action='store_true', help='Overwrite existing pcd files')
+ parser.add_argument('--verify', action='store_true', help='After conversion, read back and compare each PCD with original .bin')
+ args = parser.parse_args()
+
+ data_root = args.data_root
+ split = args.split
+ pkl_path = os.path.join(data_root, f'kitti_infos_{split}.pkl')
+ if not os.path.exists(pkl_path):
+ raise SystemExit(f'kitti infos not found: {pkl_path}')
+
+ with open(pkl_path, 'rb') as f:
+ infos = pickle.load(f)
+
+ pts_prefix = args.pts_prefix
+
+ # default out_dir: if user passed --out-dir use it, otherwise create a pcd folder
+ # next to the source pts folder. For KITTI-like paths 'training/velodyne/000001.bin'
+ # and pts_prefix='velodyne_reduced' we'll create 'Datasets/training/velodyne_reduced_pcd'
+ if args.out_dir:
+ out_dir = args.out_dir
+ else:
+ # derive parent folder from the first entry and create sibling _pcd
+ sample_key = sorted(infos.keys())[0]
+ sample_vel_path = infos[sample_key].get('velodyne_path')
+ parent = os.path.dirname(os.path.join(data_root, sample_vel_path))
+ out_dir = os.path.join(os.path.dirname(parent), f'{pts_prefix}_pcd')
+
+ os.makedirs(out_dir, exist_ok=True)
+
+ print(f'Found {len(infos)} entries in {pkl_path}')
+
+ converted = 0
+ missing = 0
+ verify_failed = 0
+ processed = 0 # counts files that would be converted (also used by --max)
+ for i, key in enumerate(sorted(infos.keys())):
+ info = infos[key]
+ vel_path = info.get('velodyne_path')
+ if vel_path is None:
+ print(f'[{key}] No velodyne_path, skipping')
+ continue
+
+ # absolute path: replace 'velodyne' component with pts_prefix (mirrors Kitti behavior)
+ vel_path_resolved = vel_path.replace('velodyne', pts_prefix)
+ bin_path = os.path.join(data_root, vel_path_resolved)
+
+ base = os.path.splitext(os.path.basename(vel_path))[0]
+ pcd_path = os.path.join(out_dir, f'{base}.pcd')
+
+ if not os.path.exists(bin_path):
+ print(f'[{key}] MISSING: {bin_path}')
+ missing += 1
+ continue
+
+ if os.path.exists(pcd_path) and not args.overwrite:
+ print(f'[{key}] SKIP (exists): {pcd_path}')
+ continue
+
+ # convert the file
+ processed += 1
+ print(f'[{key}] {bin_path} -> {pcd_path}')
+ try:
+ convert_bin_to_pcd(bin_path, pcd_path)
+ converted += 1
+ # Optional verification per file
+ if args.verify:
+ ok = compare_bin_pcd_file(bin_path, pcd_path)
+ if not ok:
+ print(f' VERIFY FAILED: {bin_path} -> {pcd_path}')
+ verify_failed += 1
+ except Exception as e:
+ print(f' ERROR converting {bin_path}: {e}')
+
+ # stop when we've processed enough files (applies to --max)
+ if args.max > 0 and processed >= args.max:
+ break
+
+ print(f'Done. Converted: {converted}, Missing: {missing}, Verify failed: {verify_failed}, Output dir: {out_dir}')
+
+
+if __name__ == '__main__':
+ main()
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/io.py b/notebooks/3D-point-pillars/pointpillars/utils/io.py
new file mode 100644
index 00000000000..a694f8abaa0
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/io.py
@@ -0,0 +1,120 @@
+import numpy as np
+import os
+import pickle
+
+_read_kitti_pcd = None
+
+def read_pickle(file_path, suffix='.pkl'):
+ assert os.path.splitext(file_path)[1] == suffix
+ with open(file_path, 'rb') as f:
+ data = pickle.load(f)
+ return data
+
+
+def write_pickle(results, file_path):
+ with open(file_path, 'wb') as f:
+ pickle.dump(results, f)
+
+
+def read_points(file_path, dim=4):
+ suffix = os.path.splitext(file_path)[1]
+ assert suffix in ['.bin', '.ply', '.pcd']
+ if suffix == '.bin':
+ return np.fromfile(file_path, dtype=np.float32).reshape(-1, dim)
+ elif suffix == '.pcd':
+ # import here to avoid circular imports: pointpillars.utils <-> pointpillars.dataset
+ global _read_kitti_pcd
+ if _read_kitti_pcd is None:
+ from pointpillars.dataset.kitti_open3d.utils import read_kitti_pcd as _impl
+ _read_kitti_pcd = _impl
+ pts = _read_kitti_pcd(file_path)
+
+ return pts.astype(np.float32)
+ else:
+ # .ply not implemented yet
+ raise NotImplementedError
+
+
+def write_points(lidar_points, file_path):
+ suffix = os.path.splitext(file_path)[1]
+ assert suffix in ['.bin', '.ply']
+ if suffix == '.bin':
+ with open(file_path, 'w') as f:
+ lidar_points.tofile(f)
+ else:
+ raise NotImplementedError
+
+
+def read_calib(file_path, extend_matrix=True):
+ with open(file_path, 'r') as f:
+ lines = f.readlines()
+ lines = [line.strip() for line in lines]
+ P0 = np.array([item for item in lines[0].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+ P1 = np.array([item for item in lines[1].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+ P2 = np.array([item for item in lines[2].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+ P3 = np.array([item for item in lines[3].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+
+ R0_rect = np.array([item for item in lines[4].split(' ')[1:]], dtype=np.float32).reshape(3, 3)
+ Tr_velo_to_cam = np.array([item for item in lines[5].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+ Tr_imu_to_velo = np.array([item for item in lines[6].split(' ')[1:]], dtype=np.float32).reshape(3, 4)
+
+ if extend_matrix:
+ P0 = np.concatenate([P0, np.array([[0, 0, 0, 1]])], axis=0)
+ P1 = np.concatenate([P1, np.array([[0, 0, 0, 1]])], axis=0)
+ P2 = np.concatenate([P2, np.array([[0, 0, 0, 1]])], axis=0)
+ P3 = np.concatenate([P3, np.array([[0, 0, 0, 1]])], axis=0)
+
+ R0_rect_extend = np.eye(4, dtype=R0_rect.dtype)
+ R0_rect_extend[:3, :3] = R0_rect
+ R0_rect = R0_rect_extend
+
+ Tr_velo_to_cam = np.concatenate([Tr_velo_to_cam, np.array([[0, 0, 0, 1]])], axis=0)
+ Tr_imu_to_velo = np.concatenate([Tr_imu_to_velo, np.array([[0, 0, 0, 1]])], axis=0)
+
+ calib_dict=dict(
+ P0=P0,
+ P1=P1,
+ P2=P2,
+ P3=P3,
+ R0_rect=R0_rect,
+ Tr_velo_to_cam=Tr_velo_to_cam,
+ Tr_imu_to_velo=Tr_imu_to_velo
+ )
+ return calib_dict
+
+
+def read_label(file_path):
+ with open(file_path, 'r') as f:
+ lines = f.readlines()
+ lines = [line.strip().split(' ') for line in lines]
+ annotation = {}
+ annotation['name'] = np.array([line[0] for line in lines])
+ annotation['truncated'] = np.array([line[1] for line in lines], dtype=np.float32)
+ annotation['occluded'] = np.array([line[2] for line in lines], dtype=np.int32)
+ annotation['alpha'] = np.array([line[3] for line in lines], dtype=np.float32)
+ annotation['bbox'] = np.array([line[4:8] for line in lines], dtype=np.float32)
+ annotation['dimensions'] = np.array([line[8:11] for line in lines], dtype=np.float32)[:, [2, 0, 1]] # hwl -> camera coordinates (lhw)
+ annotation['location'] = np.array([line[11:14] for line in lines], dtype=np.float32)
+ annotation['rotation_y'] = np.array([line[14] for line in lines], dtype=np.float32)
+
+ return annotation
+
+
+def write_label(result, file_path, suffix='.txt'):
+ '''
+ result: dict,
+ file_path: str
+ '''
+ assert os.path.splitext(file_path)[1] == suffix
+ name, truncated, occluded, alpha, bbox, dimensions, location, rotation_y, score = \
+ result['name'], result['truncated'], result['occluded'], result['alpha'], \
+ result['bbox'], result['dimensions'], result['location'], result['rotation_y'], \
+ result['score']
+
+ with open(file_path, 'w') as f:
+ for i in range(len(name)):
+ bbox_str = ' '.join(map(str, bbox[i]))
+ hwl = ' '.join(map(str, dimensions[i]))
+ xyz = ' '.join(map(str, location[i]))
+ line = f'{name[i]} {truncated[i]} {occluded[i]} {alpha[i]} {bbox_str} {hwl} {xyz} {rotation_y[i]} {score[i]}\n'
+ f.writelines(line)
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/process.py b/notebooks/3D-point-pillars/pointpillars/utils/process.py
new file mode 100644
index 00000000000..f74887c28db
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/process.py
@@ -0,0 +1,745 @@
+import copy
+import numba
+import numpy as np
+import random
+import torch
+import pdb
+from pointpillars.ops.iou3d_module import boxes_overlap_bev, boxes_iou_bev
+
+
+def setup_seed(seed=0, deterministic = True):
+ random.seed(seed)
+ np.random.seed(seed)
+ torch.manual_seed(seed)
+ torch.cuda.manual_seed_all(seed)
+ if deterministic:
+ torch.backends.cudnn.deterministic = True
+ torch.backends.cudnn.benchmark = False
+
+
+def bbox_camera2lidar(bboxes, tr_velo_to_cam, r0_rect):
+ '''
+ bboxes: shape=(N, 7)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ return: shape=(N, 7)
+ '''
+ x_size, y_size, z_size = bboxes[:, 3:4], bboxes[:, 4:5], bboxes[:, 5:6]
+ xyz_size = np.concatenate([z_size, x_size, y_size], axis=1)
+ extended_xyz = np.pad(bboxes[:, :3], ((0, 0), (0, 1)), 'constant', constant_values=1.0)
+ rt_mat = np.linalg.inv(r0_rect @ tr_velo_to_cam)
+ xyz = extended_xyz @ rt_mat.T
+ bboxes_lidar = np.concatenate([xyz[:, :3], xyz_size, bboxes[:, 6:]], axis=1)
+ return np.array(bboxes_lidar, dtype=np.float32)
+
+
+def bbox_lidar2camera(bboxes, tr_velo_to_cam, r0_rect):
+ '''
+ bboxes: shape=(N, 7)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ return: shape=(N, 7)
+ '''
+ x_size, y_size, z_size = bboxes[:, 3:4], bboxes[:, 4:5], bboxes[:, 5:6]
+ xyz_size = np.concatenate([y_size, z_size, x_size], axis=1)
+ extended_xyz = np.pad(bboxes[:, :3], ((0, 0), (0, 1)), 'constant', constant_values=1.0)
+ rt_mat = r0_rect @ tr_velo_to_cam
+ xyz = extended_xyz @ rt_mat.T
+ bboxes_camera = np.concatenate([xyz[:, :3], xyz_size, bboxes[:, 6:]], axis=1)
+ return bboxes_camera
+
+
+def points_camera2image(points, P2):
+ '''
+ points: shape=(N, 8, 3)
+ P2: shape=(4, 4)
+ return: shape=(N, 8, 2)
+ '''
+ extended_points = np.pad(points, ((0, 0), (0, 0), (0, 1)), 'constant', constant_values=1.0) # (n, 8, 4)
+ image_points = extended_points @ P2.T # (N, 8, 4)
+ image_points = image_points[:, :, :2] / image_points[:, :, 2:3]
+ return image_points
+
+
+def points_lidar2image(points, tr_velo_to_cam, r0_rect, P2):
+ '''
+ points: shape=(N, 8, 3)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ P2: shape=(4, 4)
+ return: shape=(N, 8, 2)
+ '''
+ # points = points[:, :, [1, 2, 0]]
+ extended_points = np.pad(points, ((0, 0), (0, 0), (0, 1)), 'constant', constant_values=1.0) # (N, 8, 4)
+ rt_mat = r0_rect @ tr_velo_to_cam
+ camera_points = extended_points @ rt_mat.T # (N, 8, 4)
+ # camera_points = camera_points[:, :, [1, 2, 0, 3]]
+ image_points = camera_points @ P2.T # (N, 8, 4)
+ image_points = image_points[:, :, :2] / image_points[:, :, 2:3]
+
+ return image_points
+
+
+def points_camera2lidar(points, tr_velo_to_cam, r0_rect):
+ '''
+ points: shape=(N, 8, 3)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ return: shape=(N, 8, 3)
+ '''
+ extended_xyz = np.pad(points, ((0, 0), (0, 0), (0, 1)), 'constant', constant_values=1.0)
+ rt_mat = np.linalg.inv(r0_rect @ tr_velo_to_cam)
+ xyz = extended_xyz @ rt_mat.T
+ return xyz[..., :3]
+
+
+def bbox3d2bevcorners(bboxes):
+ '''
+ bboxes: shape=(n, 7)
+
+ ^ x (-0.5 * pi)
+ |
+ | (bird's eye view)
+ (-pi) o |
+ y <-------------- (0)
+ \ / (ag)
+ \
+ \
+
+ return: shape=(n, 4, 2)
+ '''
+ centers, dims, angles = bboxes[:, :2], bboxes[:, 3:5], bboxes[:, 6]
+
+ # 1.generate bbox corner coordinates, clockwise from minimal point
+ bev_corners = np.array([[-0.5, -0.5], [-0.5, 0.5], [0.5, 0.5], [0.5, -0.5]], dtype=np.float32)
+ bev_corners = bev_corners[None, ...] * dims[:, None, :] # (1, 4, 2) * (n, 1, 2) -> (n, 4, 2)
+
+ # 2. rotate
+ rot_sin, rot_cos = np.sin(angles), np.cos(angles)
+ # in fact, -angle
+ rot_mat = np.array([[rot_cos, rot_sin],
+ [-rot_sin, rot_cos]]) # (2, 2, n)
+ rot_mat = np.transpose(rot_mat, (2, 1, 0)) # (N, 2, 2)
+ bev_corners = bev_corners @ rot_mat # (n, 4, 2)
+
+ # 3. translate to centers
+ bev_corners += centers[:, None, :]
+ return bev_corners.astype(np.float32)
+
+
+def bbox3d2corners(bboxes):
+ '''
+ bboxes: shape=(n, 7)
+ return: shape=(n, 8, 3)
+ ^ z x 6 ------ 5
+ | / / | / |
+ | / 2 -|---- 1 |
+ y | / | | | |
+ <------|o | 7 -----| 4
+ |/ o |/
+ 3 ------ 0
+ x: front, y: left, z: top
+ '''
+ centers, dims, angles = bboxes[:, :3], bboxes[:, 3:6], bboxes[:, 6]
+
+ # 1.generate bbox corner coordinates, clockwise from minimal point
+ bboxes_corners = np.array([[-0.5, -0.5, 0], [-0.5, -0.5, 1.0], [-0.5, 0.5, 1.0], [-0.5, 0.5, 0.0],
+ [0.5, -0.5, 0], [0.5, -0.5, 1.0], [0.5, 0.5, 1.0], [0.5, 0.5, 0.0]],
+ dtype=np.float32)
+ bboxes_corners = bboxes_corners[None, :, :] * dims[:, None, :] # (1, 8, 3) * (n, 1, 3) -> (n, 8, 3)
+
+ # 2. rotate around z axis
+ rot_sin, rot_cos = np.sin(angles), np.cos(angles)
+ # in fact, -angle
+ rot_mat = np.array([[rot_cos, rot_sin, np.zeros_like(rot_cos)],
+ [-rot_sin, rot_cos, np.zeros_like(rot_cos)],
+ [np.zeros_like(rot_cos), np.zeros_like(rot_cos), np.ones_like(rot_cos)]],
+ dtype=np.float32) # (3, 3, n)
+ rot_mat = np.transpose(rot_mat, (2, 1, 0)) # (n, 3, 3)
+ bboxes_corners = bboxes_corners @ rot_mat # (n, 8, 3)
+
+ # 3. translate to centers
+ bboxes_corners += centers[:, None, :]
+ return bboxes_corners
+
+
+def bbox3d2corners_camera(bboxes):
+ '''
+ bboxes: shape=(n, 7)
+ return: shape=(n, 8, 3)
+ z (front) 6 ------ 5
+ / / | / |
+ / 2 -|---- 1 |
+ / | | | |
+ |o ------> x(right) | 7 -----| 4
+ | |/ o |/
+ | 3 ------ 0
+ |
+ v y(down)
+ '''
+ centers, dims, angles = bboxes[:, :3], bboxes[:, 3:6], bboxes[:, 6]
+
+ # 1.generate bbox corner coordinates, clockwise from minimal point
+ bboxes_corners = np.array([[0.5, 0.0, -0.5], [0.5, -1.0, -0.5], [-0.5, -1.0, -0.5], [-0.5, 0.0, -0.5],
+ [0.5, 0.0, 0.5], [0.5, -1.0, 0.5], [-0.5, -1.0, 0.5], [-0.5, 0.0, 0.5]],
+ dtype=np.float32)
+ bboxes_corners = bboxes_corners[None, :, :] * dims[:, None, :] # (1, 8, 3) * (n, 1, 3) -> (n, 8, 3)
+
+ # 2. rotate around y axis
+ rot_sin, rot_cos = np.sin(angles), np.cos(angles)
+ # in fact, angle
+ rot_mat = np.array([[rot_cos, np.zeros_like(rot_cos), rot_sin],
+ [np.zeros_like(rot_cos), np.ones_like(rot_cos), np.zeros_like(rot_cos)],
+ [-rot_sin, np.zeros_like(rot_cos), rot_cos]],
+ dtype=np.float32) # (3, 3, n)
+ rot_mat = np.transpose(rot_mat, (2, 1, 0)) # (n, 3, 3)
+ bboxes_corners = bboxes_corners @ rot_mat # (n, 8, 3)
+
+ # 3. translate to centers
+ bboxes_corners += centers[:, None, :]
+ return bboxes_corners
+
+
+def group_rectangle_vertexs(bboxes_corners):
+ '''
+ bboxes_corners: shape=(n, 8, 3)
+ return: shape=(n, 6, 4, 3)
+ '''
+ rec1 = np.stack([bboxes_corners[:, 0], bboxes_corners[:, 1], bboxes_corners[:, 3], bboxes_corners[:, 2]], axis=1) # (n, 4, 3)
+ rec2 = np.stack([bboxes_corners[:, 4], bboxes_corners[:, 7], bboxes_corners[:, 6], bboxes_corners[:, 5]], axis=1) # (n, 4, 3)
+ rec3 = np.stack([bboxes_corners[:, 0], bboxes_corners[:, 4], bboxes_corners[:, 5], bboxes_corners[:, 1]], axis=1) # (n, 4, 3)
+ rec4 = np.stack([bboxes_corners[:, 2], bboxes_corners[:, 6], bboxes_corners[:, 7], bboxes_corners[:, 3]], axis=1) # (n, 4, 3)
+ rec5 = np.stack([bboxes_corners[:, 1], bboxes_corners[:, 5], bboxes_corners[:, 6], bboxes_corners[:, 2]], axis=1) # (n, 4, 3)
+ rec6 = np.stack([bboxes_corners[:, 0], bboxes_corners[:, 3], bboxes_corners[:, 7], bboxes_corners[:, 4]], axis=1) # (n, 4, 3)
+ group_rectangle_vertexs = np.stack([rec1, rec2, rec3, rec4, rec5, rec6], axis=1)
+ return group_rectangle_vertexs
+
+
+@numba.jit(nopython=True)
+def bevcorner2alignedbbox(bev_corners):
+ '''
+ bev_corners: shape=(N, 4, 2)
+ return: shape=(N, 4)
+ '''
+ # xmin, xmax = np.min(bev_corners[:, :, 0], axis=-1), np.max(bev_corners[:, :, 0], axis=-1)
+ # ymin, ymax = np.min(bev_corners[:, :, 1], axis=-1), np.max(bev_corners[:, :, 1], axis=-1)
+
+ # why we don't implement like the above ? please see
+ # https://numba.pydata.org/numba-doc/latest/reference/numpysupported.html#calculation
+ n = len(bev_corners)
+ alignedbbox = np.zeros((n, 4), dtype=np.float32)
+ for i in range(n):
+ cur_bev = bev_corners[i]
+ alignedbbox[i, 0] = np.min(cur_bev[:, 0])
+ alignedbbox[i, 2] = np.max(cur_bev[:, 0])
+ alignedbbox[i, 1] = np.min(cur_bev[:, 1])
+ alignedbbox[i, 3] = np.max(cur_bev[:, 1])
+ return alignedbbox
+
+
+# modified from https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/datasets/pipelines/data_augment_utils.py#L31
+@numba.jit(nopython=True)
+def box_collision_test(boxes, qboxes, clockwise=True):
+ """Box collision test.
+ Args:
+ boxes (np.ndarray): Corners of current boxes. # (n1, 4, 2)
+ qboxes (np.ndarray): Boxes to be avoid colliding. # (n2, 4, 2)
+ clockwise (bool, optional): Whether the corners are in
+ clockwise order. Default: True.
+ return: shape=(n1, n2)
+ """
+ N = boxes.shape[0]
+ K = qboxes.shape[0]
+ ret = np.zeros((N, K), dtype=np.bool_)
+ slices = np.array([1, 2, 3, 0])
+ lines_boxes = np.stack((boxes, boxes[:, slices, :]),
+ axis=2) # [N, 4, 2(line), 2(xy)]
+ lines_qboxes = np.stack((qboxes, qboxes[:, slices, :]), axis=2)
+ # vec = np.zeros((2,), dtype=boxes.dtype)
+ boxes_standup = bevcorner2alignedbbox(boxes)
+ qboxes_standup = bevcorner2alignedbbox(qboxes)
+ for i in range(N):
+ for j in range(K):
+ # calculate standup first
+ iw = (
+ min(boxes_standup[i, 2], qboxes_standup[j, 2]) -
+ max(boxes_standup[i, 0], qboxes_standup[j, 0]))
+ if iw > 0:
+ ih = (
+ min(boxes_standup[i, 3], qboxes_standup[j, 3]) -
+ max(boxes_standup[i, 1], qboxes_standup[j, 1]))
+ if ih > 0:
+ for k in range(4):
+ for box_l in range(4):
+ A = lines_boxes[i, k, 0]
+ B = lines_boxes[i, k, 1]
+ C = lines_qboxes[j, box_l, 0]
+ D = lines_qboxes[j, box_l, 1]
+ acd = (D[1] - A[1]) * (C[0] -
+ A[0]) > (C[1] - A[1]) * (
+ D[0] - A[0])
+ bcd = (D[1] - B[1]) * (C[0] -
+ B[0]) > (C[1] - B[1]) * (
+ D[0] - B[0])
+ if acd != bcd:
+ abc = (C[1] - A[1]) * (B[0] - A[0]) > (
+ B[1] - A[1]) * (
+ C[0] - A[0])
+ abd = (D[1] - A[1]) * (B[0] - A[0]) > (
+ B[1] - A[1]) * (
+ D[0] - A[0])
+ if abc != abd:
+ ret[i, j] = True # collision.
+ break
+ if ret[i, j] is True:
+ break
+ if ret[i, j] is False:
+ # now check complete overlap.
+ # box overlap qbox:
+ box_overlap_qbox = True
+ for box_l in range(4): # point l in qboxes
+ for k in range(4): # corner k in boxes
+ vec = boxes[i, k] - boxes[i, (k + 1) % 4]
+ if clockwise:
+ vec = -vec
+ cross = vec[1] * (
+ boxes[i, k, 0] - qboxes[j, box_l, 0])
+ cross -= vec[0] * (
+ boxes[i, k, 1] - qboxes[j, box_l, 1])
+ if cross >= 0:
+ box_overlap_qbox = False
+ break
+ if box_overlap_qbox is False:
+ break
+
+ if box_overlap_qbox is False:
+ qbox_overlap_box = True
+ for box_l in range(4): # point box_l in boxes
+ for k in range(4): # corner k in qboxes
+ vec = qboxes[j, k] - qboxes[j, (k + 1) % 4]
+ if clockwise:
+ vec = -vec
+ cross = vec[1] * (
+ qboxes[j, k, 0] - boxes[i, box_l, 0])
+ cross -= vec[0] * (
+ qboxes[j, k, 1] - boxes[i, box_l, 1])
+ if cross >= 0: #
+ qbox_overlap_box = False
+ break
+ if qbox_overlap_box is False:
+ break
+ if qbox_overlap_box:
+ ret[i, j] = True # collision.
+ else:
+ ret[i, j] = True # collision.
+ return ret
+
+
+def group_plane_equation(bbox_group_rectangle_vertexs):
+ '''
+ bbox_group_rectangle_vertexs: shape=(n, 6, 4, 3)
+ return: shape=(n, 6, 4)
+ '''
+ # 1. generate vectors for a x b
+ vectors = bbox_group_rectangle_vertexs[:, :, :2] - bbox_group_rectangle_vertexs[:, :, 1:3]
+ normal_vectors = np.cross(vectors[:, :, 0], vectors[:, :, 1]) # (n, 6, 3)
+ normal_d = np.einsum('ijk,ijk->ij', bbox_group_rectangle_vertexs[:, :, 0], normal_vectors) # (n, 6)
+ plane_equation_params = np.concatenate([normal_vectors, -normal_d[:, :, None]], axis=-1)
+ return plane_equation_params
+
+
+@numba.jit(nopython=True)
+def points_in_bboxes(points, plane_equation_params):
+ '''
+ points: shape=(N, 3)
+ plane_equation_params: shape=(n, 6, 4)
+ return: shape=(N, n), bool
+ '''
+ N, n = len(points), len(plane_equation_params)
+ m = plane_equation_params.shape[1]
+ masks = np.ones((N, n), dtype=np.bool_)
+ for i in range(N):
+ x, y, z = points[i, :3]
+ for j in range(n):
+ bbox_plane_equation_params = plane_equation_params[j]
+ for k in range(m):
+ a, b, c, d = bbox_plane_equation_params[k]
+ if a * x + b * y + c * z + d >= 0:
+ masks[i][j] = False
+ break
+ return masks
+
+
+def remove_pts_in_bboxes(points, bboxes, rm=True):
+ '''
+ points: shape=(N, 3)
+ bboxes: shape=(n, 7)
+ return: shape=(N, n), bool
+ '''
+ # 1. get 6 groups of rectangle vertexs
+ bboxes_corners = bbox3d2corners(bboxes) # (n, 8, 3)
+ bbox_group_rectangle_vertexs = group_rectangle_vertexs(bboxes_corners) # (n, 6, 4, 3)
+
+ # 2. calculate plane equation: ax + by + cd + d = 0
+ group_plane_equation_params = group_plane_equation(bbox_group_rectangle_vertexs)
+
+ # 3. Judge each point inside or outside the bboxes
+ # if point (x0, y0, z0) lies on the direction of normal vector(a, b, c), then ax0 + by0 + cz0 + d > 0.
+ masks = points_in_bboxes(points, group_plane_equation_params) # (N, n)
+
+ if not rm:
+ return masks
+
+ # 4. remove point insider the bboxes
+ masks = np.any(masks, axis=-1)
+
+ return points[~masks]
+
+
+# modified from https://github.com/open-mmlab/mmdetection3d/blob/master/mmdet3d/core/bbox/structures/utils.py#L11
+def limit_period(val, offset=0.5, period=np.pi):
+ """
+ val: array or float
+ offset: float
+ period: float
+ return: Value in the range of [-offset * period, (1-offset) * period]
+ """
+ limited_val = val - np.floor(val / period + offset) * period
+ return limited_val
+
+
+def nearest_bev(bboxes):
+ '''
+ bboxes: (n, 7), (x, y, z, w, l, h, theta)
+ return: (n, 4), (x1, y1, x2, y2)
+ '''
+ bboxes_bev = copy.deepcopy(bboxes[:, [0, 1, 3, 4]])
+ bboxes_angle = limit_period(bboxes[:, 6].cpu(), offset=0.5, period=np.pi).to(bboxes_bev)
+ bboxes_bev = torch.where(torch.abs(bboxes_angle[:, None]) > np.pi / 4, bboxes_bev[:, [0, 1, 3, 2]], bboxes_bev)
+
+ bboxes_xy = bboxes_bev[:, :2]
+ bboxes_wl = bboxes_bev[:, 2:]
+ bboxes_bev_x1y1x2y2 = torch.cat([bboxes_xy - bboxes_wl / 2, bboxes_xy + bboxes_wl / 2], dim=-1)
+ return bboxes_bev_x1y1x2y2
+
+
+def iou2d(bboxes1, bboxes2, metric=0):
+ '''
+ bboxes1: (n, 4), (x1, y1, x2, y2)
+ bboxes2: (m, 4), (x1, y1, x2, y2)
+ return: (n, m)
+ '''
+ bboxes_x1 = torch.maximum(bboxes1[:, 0][:, None], bboxes2[:, 0][None, :]) # (n, m)
+ bboxes_y1 = torch.maximum(bboxes1[:, 1][:, None], bboxes2[:, 1][None, :]) # (n, m)
+ bboxes_x2 = torch.minimum(bboxes1[:, 2][:, None], bboxes2[:, 2][None, :])
+ bboxes_y2 = torch.minimum(bboxes1[:, 3][:, None], bboxes2[:, 3][None, :])
+
+ bboxes_w = torch.clamp(bboxes_x2 - bboxes_x1, min=0)
+ bboxes_h = torch.clamp(bboxes_y2 - bboxes_y1, min=0)
+
+ iou_area = bboxes_w * bboxes_h # (n, m)
+
+ bboxes1_wh = bboxes1[:, 2:] - bboxes1[:, :2]
+ area1 = bboxes1_wh[:, 0] * bboxes1_wh[:, 1] # (n, )
+ bboxes2_wh = bboxes2[:, 2:] - bboxes2[:, :2]
+ area2 = bboxes2_wh[:, 0] * bboxes2_wh[:, 1] # (m, )
+ if metric == 0:
+ iou = iou_area / (area1[:, None] + area2[None, :] - iou_area + 1e-8)
+ elif metric == 1:
+ iou = iou_area / (area1[:, None] + 1e-8)
+ return iou
+
+
+def iou2d_nearest(bboxes1, bboxes2):
+ '''
+ bboxes1: (n, 7), (x, y, z, w, l, h, theta)
+ bboxes2: (m, 7),
+ return: (n, m)
+ '''
+ bboxes1_bev = nearest_bev(bboxes1)
+ bboxes2_bev = nearest_bev(bboxes2)
+ iou = iou2d(bboxes1_bev, bboxes2_bev)
+ return iou
+
+
+def iou3d(bboxes1, bboxes2):
+ '''
+ bboxes1: (n, 7), (x, y, z, w, l, h, theta)
+ bboxes2: (m, 7)
+ return: (n, m)
+ '''
+ # 1. height overlap
+ bboxes1_bottom, bboxes2_bottom = bboxes1[:, 2], bboxes2[:, 2] # (n, ), (m, )
+ bboxes1_top, bboxes2_top = bboxes1[:, 2] + bboxes1[:, 5], bboxes2[:, 2] + bboxes2[:, 5] # (n, ), (m, )
+ bboxes_bottom = torch.maximum(bboxes1_bottom[:, None], bboxes2_bottom[None, :]) # (n, m)
+ bboxes_top = torch.minimum(bboxes1_top[:, None], bboxes2_top[None, :])
+ height_overlap = torch.clamp(bboxes_top - bboxes_bottom, min=0)
+
+ # 2. bev overlap
+ bboxes1_x1y1 = bboxes1[:, :2] - bboxes1[:, 3:5] / 2
+ bboxes1_x2y2 = bboxes1[:, :2] + bboxes1[:, 3:5] / 2
+ bboxes2_x1y1 = bboxes2[:, :2] - bboxes2[:, 3:5] / 2
+ bboxes2_x2y2 = bboxes2[:, :2] + bboxes2[:, 3:5] / 2
+ bboxes1_bev = torch.cat([bboxes1_x1y1, bboxes1_x2y2, bboxes1[:, 6:]], dim=-1)
+ bboxes2_bev = torch.cat([bboxes2_x1y1, bboxes2_x2y2, bboxes2[:, 6:]], dim=-1)
+ bev_overlap = boxes_overlap_bev(bboxes1_bev, bboxes2_bev) # (n, m)
+
+ # 3. overlap and volume
+ overlap = height_overlap * bev_overlap
+ volume1 = bboxes1[:, 3] * bboxes1[:, 4] * bboxes1[:, 5]
+ volume2 = bboxes2[:, 3] * bboxes2[:, 4] * bboxes2[:, 5]
+ volume = volume1[:, None] + volume2[None, :] # (n, m)
+
+ # 4. iou
+ iou = overlap / (volume - overlap + 1e-8)
+
+ return iou
+
+
+def iou3d_camera(bboxes1, bboxes2):
+ '''
+ bboxes1: (n, 7), (x, y, z, w, l, h, theta)
+ bboxes2: (m, 7)
+ return: (n, m)
+ '''
+ # 1. height overlap
+ bboxes1_bottom, bboxes2_bottom = bboxes1[:, 1] - bboxes1[:, 4], bboxes2[:, 1] - bboxes2[:, 4] # (n, ), (m, )
+ bboxes1_top, bboxes2_top = bboxes1[:, 1], bboxes2[:, 1] # (n, ), (m, )
+ bboxes_bottom = torch.maximum(bboxes1_bottom[:, None], bboxes2_bottom[None, :]) # (n, m)
+ bboxes_top = torch.minimum(bboxes1_top[:, None], bboxes2_top[None, :])
+ height_overlap = torch.clamp(bboxes_top - bboxes_bottom, min=0)
+
+ # 2. bev overlap
+ bboxes1_x1y1 = bboxes1[:, [0, 2]] - bboxes1[:, [3, 5]] / 2
+ bboxes1_x2y2 = bboxes1[:, [0, 2]] + bboxes1[:, [3, 5]] / 2
+ bboxes2_x1y1 = bboxes2[:, [0, 2]] - bboxes2[:, [3, 5]] / 2
+ bboxes2_x2y2 = bboxes2[:, [0, 2]] + bboxes2[:, [3, 5]] / 2
+ bboxes1_bev = torch.cat([bboxes1_x1y1, bboxes1_x2y2, bboxes1[:, 6:]], dim=-1)
+ bboxes2_bev = torch.cat([bboxes2_x1y1, bboxes2_x2y2, bboxes2[:, 6:]], dim=-1)
+ bev_overlap = boxes_overlap_bev(bboxes1_bev, bboxes2_bev) # (n, m)
+
+ # 3. overlap and volume
+ overlap = height_overlap * bev_overlap
+ volume1 = bboxes1[:, 3] * bboxes1[:, 4] * bboxes1[:, 5]
+ volume2 = bboxes2[:, 3] * bboxes2[:, 4] * bboxes2[:, 5]
+ volume = volume1[:, None] + volume2[None, :] # (n, m)
+
+ # 4. iou
+ iou = overlap / (volume - overlap + 1e-8)
+
+ return iou
+
+
+def iou_bev(bboxes1, bboxes2):
+ '''
+ bboxes1: (n, 5), (x, z, w, h, theta)
+ bboxes2: (m, 5)
+ return: (n, m)
+ '''
+ bboxes1_x1y1 = bboxes1[:, :2] - bboxes1[:, 2:4] / 2
+ bboxes1_x2y2 = bboxes1[:, :2] + bboxes1[:, 2:4] / 2
+ bboxes2_x1y1 = bboxes2[:, :2] - bboxes2[:, 2:4] / 2
+ bboxes2_x2y2 = bboxes2[:, :2] + bboxes2[:, 2:4] / 2
+ bboxes1_bev = torch.cat([bboxes1_x1y1, bboxes1_x2y2, bboxes1[:, 4:]], dim=-1)
+ bboxes2_bev = torch.cat([bboxes2_x1y1, bboxes2_x2y2, bboxes2[:, 4:]], dim=-1)
+ bev_overlap = boxes_iou_bev(bboxes1_bev, bboxes2_bev) # (n, m)
+
+ return bev_overlap
+
+
+def keep_bbox_from_image_range(result, tr_velo_to_cam, r0_rect, P2, image_shape):
+ '''
+ result: dict(lidar_bboxes, labels, scores)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ P2: shape=(4, 4)
+ image_shape: (h, w)
+ return: dict(lidar_bboxes, labels, scores, bboxes2d, camera_bboxes)
+ '''
+ h, w = image_shape
+
+ lidar_bboxes = result['lidar_bboxes']
+ labels = result['labels']
+ scores = result['scores']
+ camera_bboxes = bbox_lidar2camera(lidar_bboxes, tr_velo_to_cam, r0_rect) # (n, 7)
+ bboxes_points = bbox3d2corners_camera(camera_bboxes) # (n, 8, 3)
+ image_points = points_camera2image(bboxes_points, P2) # (n, 8, 2)
+ image_x1y1 = np.min(image_points, axis=1) # (n, 2)
+ image_x1y1 = np.maximum(image_x1y1, 0)
+ image_x2y2 = np.max(image_points, axis=1) # (n, 2)
+ image_x2y2 = np.minimum(image_x2y2, [w, h])
+ bboxes2d = np.concatenate([image_x1y1, image_x2y2], axis=-1)
+
+ keep_flag = (image_x1y1[:, 0] < w) & (image_x1y1[:, 1] < h) & (image_x2y2[:, 0] > 0) & (image_x2y2[:, 1] > 0)
+
+ result = {
+ 'lidar_bboxes': lidar_bboxes[keep_flag],
+ 'labels': labels[keep_flag],
+ 'scores': scores[keep_flag],
+ 'bboxes2d': bboxes2d[keep_flag],
+ 'camera_bboxes': camera_bboxes[keep_flag]
+ }
+ return result
+
+
+def keep_bbox_from_lidar_range(result, pcd_limit_range):
+ '''
+ result: dict(lidar_bboxes, labels, scores, bboxes2d, camera_bboxes)
+ pcd_limit_range: []
+ return: dict(lidar_bboxes, labels, scores, bboxes2d, camera_bboxes)
+ '''
+ lidar_bboxes, labels, scores = result['lidar_bboxes'], result['labels'], result['scores']
+ if 'bboxes2d' not in result:
+ result['bboxes2d'] = np.zeros_like(lidar_bboxes[:, :4])
+ if 'camera_bboxes' not in result:
+ result['camera_bboxes'] = np.zeros_like(lidar_bboxes)
+ bboxes2d, camera_bboxes = result['bboxes2d'], result['camera_bboxes']
+ flag1 = lidar_bboxes[:, :3] > pcd_limit_range[:3][None, :] # (n, 3)
+ flag2 = lidar_bboxes[:, :3] < pcd_limit_range[3:][None, :] # (n, 3)
+ keep_flag = np.all(flag1, axis=-1) & np.all(flag2, axis=-1)
+
+ result = {
+ 'lidar_bboxes': lidar_bboxes[keep_flag],
+ 'labels': labels[keep_flag],
+ 'scores': scores[keep_flag],
+ 'bboxes2d': bboxes2d[keep_flag],
+ 'camera_bboxes': camera_bboxes[keep_flag]
+ }
+ return result
+
+
+def points_in_bboxes_v2(points, r0_rect, tr_velo_to_cam, dimensions, location, rotation_y, name):
+ '''
+ points: shape=(N, 4)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ dimensions: shape=(n, 3)
+ location: shape=(n, 3)
+ rotation_y: shape=(n, )
+ name: shape=(n, )
+ return:
+ indices: shape=(N, n_valid_bbox), indices[i, j] denotes whether point i is in bbox j.
+ n_total_bbox: int.
+ n_valid_bbox: int, not including 'DontCare'
+ bboxes_lidar: shape=(n_valid_bbox, 7)
+ name: shape=(n_valid_bbox, )
+ '''
+ n_total_bbox = len(dimensions)
+ n_valid_bbox = len([item for item in name if item != 'DontCare'])
+ location, dimensions = location[:n_valid_bbox], dimensions[:n_valid_bbox]
+ rotation_y, name = rotation_y[:n_valid_bbox], name[:n_valid_bbox]
+ bboxes_camera = np.concatenate([location, dimensions, rotation_y[:, None]], axis=1)
+ bboxes_lidar = bbox_camera2lidar(bboxes_camera, tr_velo_to_cam, r0_rect)
+ bboxes_corners = bbox3d2corners(bboxes_lidar)
+ group_rectangle_vertexs_v = group_rectangle_vertexs(bboxes_corners)
+ frustum_surfaces = group_plane_equation(group_rectangle_vertexs_v)
+ indices = points_in_bboxes(points[:, :3], frustum_surfaces) # (N, n), N is points num, n is bboxes number
+ return indices, n_total_bbox, n_valid_bbox, bboxes_lidar, name
+
+
+def get_points_num_in_bbox(points, r0_rect, tr_velo_to_cam, dimensions, location, rotation_y, name):
+ '''
+ points: shape=(N, 4)
+ tr_velo_to_cam: shape=(4, 4)
+ r0_rect: shape=(4, 4)
+ dimensions: shape=(n, 3)
+ location: shape=(n, 3)
+ rotation_y: shape=(n, )
+ name: shape=(n, )
+ return: shape=(n, )
+ '''
+ indices, n_total_bbox, n_valid_bbox, bboxes_lidar, name = \
+ points_in_bboxes_v2(
+ points=points,
+ r0_rect=r0_rect,
+ tr_velo_to_cam=tr_velo_to_cam,
+ dimensions=dimensions,
+ location=location,
+ rotation_y=rotation_y,
+ name=name)
+ points_num = np.sum(indices, axis=0)
+ non_valid_points_num = [-1] * (n_total_bbox - n_valid_bbox)
+ points_num = np.concatenate([points_num, non_valid_points_num], axis=0)
+ return np.array(points_num, dtype=np.int32)
+
+
+# Modified from https://github.com/open-mmlab/mmdetection3d/blob/f45977008a52baaf97640a0e9b2bbe5ea1c4be34/mmdet3d/core/bbox/box_np_ops.py#L609
+def remove_outside_points(points, r0_rect, tr_velo_to_cam, P2, image_shape):
+ """Remove points which are outside of image.
+ Args:
+ points (np.ndarray, shape=[N, 3+dims]): Total points.
+ rect (np.ndarray, shape=[4, 4]): Matrix to project points in
+ specific camera coordinate (e.g. CAM2) to CAM0.
+ Trv2c (np.ndarray, shape=[4, 4]): Matrix to project points in
+ camera coordinate to lidar coordinate.
+ P2 (p.array, shape=[4, 4]): Intrinsics of Camera2.
+ image_shape (list[int]): Shape of image.
+ Returns:
+ np.ndarray, shape=[N, 3+dims]: Filtered points.
+ """
+ # 5x faster than remove_outside_points_v1(2ms vs 10ms)
+ C, R, T = projection_matrix_to_CRT_kitti(P2)
+ image_bbox = [0, 0, image_shape[1], image_shape[0]]
+ frustum = get_frustum(image_bbox, C)
+ frustum -= T
+ frustum = np.linalg.inv(R) @ frustum.T
+ frustum = points_camera2lidar(frustum.T[None, ...], tr_velo_to_cam, r0_rect) # (1, 8, 3)
+ group_rectangle_vertexs_v = group_rectangle_vertexs(frustum)
+ frustum_surfaces = group_plane_equation(group_rectangle_vertexs_v)
+ indices = points_in_bboxes(points[:, :3], frustum_surfaces) # (N, 1)
+ points = points[indices.reshape([-1])]
+ return points
+
+
+# Copied from https://github.com/open-mmlab/mmdetection3d/blob/f45977008a52baaf97640a0e9b2bbe5ea1c4be34/mmdet3d/core/bbox/box_np_ops.py#L609
+def projection_matrix_to_CRT_kitti(proj):
+ """Split projection matrix of kitti.
+ P = C @ [R|T]
+ C is upper triangular matrix, so we need to inverse CR and use QR
+ stable for all kitti camera projection matrix.
+ Args:
+ proj (p.array, shape=[4, 4]): Intrinsics of camera.
+ Returns:
+ tuple[np.ndarray]: Splited matrix of C, R and T.
+ """
+
+ CR = proj[0:3, 0:3]
+ CT = proj[0:3, 3]
+ RinvCinv = np.linalg.inv(CR)
+ Rinv, Cinv = np.linalg.qr(RinvCinv)
+ C = np.linalg.inv(Cinv)
+ R = np.linalg.inv(Rinv)
+ T = Cinv @ CT
+ return C, R, T
+
+
+# Copied from https://github.com/open-mmlab/mmdetection3d/blob/f45977008a52baaf97640a0e9b2bbe5ea1c4be34/mmdet3d/core/bbox/box_np_ops.py#L661
+def get_frustum(bbox_image, C, near_clip=0.001, far_clip=100):
+ """Get frustum corners in camera coordinates.
+ Args:
+ bbox_image (list[int]): box in image coordinates.
+ C (np.ndarray): Intrinsics.
+ near_clip (float, optional): Nearest distance of frustum.
+ Defaults to 0.001.
+ far_clip (float, optional): Farthest distance of frustum.
+ Defaults to 100.
+ Returns:
+ np.ndarray, shape=[8, 3]: coordinates of frustum corners.
+ """
+ fku = C[0, 0]
+ fkv = -C[1, 1]
+ u0v0 = C[0:2, 2]
+ z_points = np.array(
+ [near_clip] * 4 + [far_clip] * 4, dtype=C.dtype)[:, np.newaxis]
+ b = bbox_image
+ box_corners = np.array(
+ [[b[0], b[1]], [b[0], b[3]], [b[2], b[3]], [b[2], b[1]]],
+ dtype=C.dtype)
+ near_box_corners = (box_corners - u0v0) / np.array(
+ [fku / near_clip, -fkv / near_clip], dtype=C.dtype)
+ far_box_corners = (box_corners - u0v0) / np.array(
+ [fku / far_clip, -fkv / far_clip], dtype=C.dtype)
+ ret_xy = np.concatenate([near_box_corners, far_box_corners],
+ axis=0) # [8, 2]
+ ret_xyz = np.concatenate([ret_xy, z_points], axis=1)
+ return ret_xyz
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/viewpoint.json b/notebooks/3D-point-pillars/pointpillars/utils/viewpoint.json
new file mode 100644
index 00000000000..aebb9e11bf1
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/viewpoint.json
@@ -0,0 +1,30 @@
+{
+ "class_name" : "PinholeCameraParameters",
+ "extrinsic" :
+ [
+ 0.013862749108655318,
+ -0.99931910700250171,
+ 0.034192785304405081,
+ 0,
+ -0.99751226840734264,
+ -0.011457761025003947,
+ 0.069555690558944339,
+ 0,
+ -0.069116557813509449,
+ -0.035071955919460274,
+ -0.99699190535530191,
+ 0,
+ 7.0392596000563916,
+ 14.768969974020909,
+ 101.08753655485596,
+ 1
+ ],
+ "intrinsic" :
+ {
+ "height" : 1056,
+ "intrinsic_matrix" : [ 914.52282639636724, 0, 0, 0, 914.52282639636724, 0, 927, 527.5, 1 ],
+ "width" : 1855
+ },
+ "version_major" : 1,
+ "version_minor" : 0
+}
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pointpillars/utils/vis_o3d.py b/notebooks/3D-point-pillars/pointpillars/utils/vis_o3d.py
new file mode 100644
index 00000000000..8ecf11a050b
--- /dev/null
+++ b/notebooks/3D-point-pillars/pointpillars/utils/vis_o3d.py
@@ -0,0 +1,122 @@
+import cv2
+import numpy as np
+import open3d as o3d
+import os
+from pointpillars.utils import bbox3d2corners
+
+
+COLORS = [[1, 0, 0], [0, 1, 0], [0, 0, 1], [1, 1, 0]]
+COLORS_IMG = [[0, 0, 255], [0, 255, 0], [255, 0, 0], [0, 255, 255]]
+
+LINES = [
+ [0, 1],
+ [1, 2],
+ [2, 3],
+ [3, 0],
+ [4, 5],
+ [5, 6],
+ [6, 7],
+ [7, 4],
+ [2, 6],
+ [7, 3],
+ [1, 5],
+ [4, 0]
+ ]
+
+
+def npy2ply(npy):
+ ply = o3d.geometry.PointCloud()
+ ply.points = o3d.utility.Vector3dVector(npy[:, :3])
+ density = npy[:, 3]
+ colors = [[item, item, item] for item in density]
+ ply.colors = o3d.utility.Vector3dVector(colors)
+ return ply
+
+
+def ply2npy(ply):
+ return np.array(ply.points)
+
+
+def bbox_obj(points, color=[1, 0, 0]):
+ colors = [color for i in range(len(LINES))]
+ line_set = o3d.geometry.LineSet(
+ points=o3d.utility.Vector3dVector(points),
+ lines=o3d.utility.Vector2iVector(LINES),
+ )
+ line_set.colors = o3d.utility.Vector3dVector(colors)
+ return line_set
+
+
+def vis_core(plys):
+ vis = o3d.visualization.Visualizer()
+ vis.create_window()
+
+ PAR = os.path.dirname(os.path.abspath(__file__))
+ ctr = vis.get_view_control()
+ param = o3d.io.read_pinhole_camera_parameters(os.path.join(PAR, 'viewpoint.json'))
+ for ply in plys:
+ vis.add_geometry(ply)
+ ctr.convert_from_pinhole_camera_parameters(param)
+
+ vis.run()
+ # param = vis.get_view_control().convert_to_pinhole_camera_parameters()
+ # o3d.io.write_pinhole_camera_parameters(os.path.join(PAR, 'viewpoint.json'), param)
+ vis.destroy_window()
+
+
+def vis_pc(pc, bboxes=None, labels=None):
+ '''
+ pc: ply or np.ndarray (N, 4)
+ bboxes: np.ndarray, (n, 7) or (n, 8, 3)
+ labels: (n, )
+ '''
+ if isinstance(pc, np.ndarray):
+ pc = npy2ply(pc)
+
+ mesh_frame = o3d.geometry.TriangleMesh.create_coordinate_frame(
+ size=10, origin=[0, 0, 0])
+
+ if bboxes is None:
+ vis_core([pc, mesh_frame])
+ return
+
+ if len(bboxes.shape) == 2:
+ bboxes = bbox3d2corners(bboxes)
+
+ vis_objs = [pc, mesh_frame]
+ for i in range(len(bboxes)):
+ bbox = bboxes[i]
+ if labels is None:
+ color = [1, 1, 0]
+ else:
+ if labels[i] >= 0 and labels[i] < 3:
+ color = COLORS[labels[i]]
+ else:
+ color = COLORS[-1]
+ vis_objs.append(bbox_obj(bbox, color=color))
+ vis_core(vis_objs)
+
+
+def vis_img_3d(img, image_points, labels, rt=True):
+ '''
+ img: (h, w, 3)
+ image_points: (n, 8, 2)
+ labels: (n, )
+ '''
+
+ for i in range(len(image_points)):
+ label = labels[i]
+ bbox_points = image_points[i] # (8, 2)
+ if label >= 0 and label < 3:
+ color = COLORS_IMG[label]
+ else:
+ color = COLORS_IMG[-1]
+ for line_id in LINES:
+ x1, y1 = bbox_points[line_id[0]]
+ x2, y2 = bbox_points[line_id[1]]
+ x1, y1, x2, y2 = int(x1), int(y1), int(x2), int(y2)
+ cv2.line(img, (x1, y1), (x2, y2), color, 1)
+ if rt:
+ return img
+ cv2.imshow('bbox', img)
+ cv2.waitKey(0)
diff --git a/notebooks/3D-point-pillars/pre_process_kitti.py b/notebooks/3D-point-pillars/pre_process_kitti.py
new file mode 100644
index 00000000000..566b84501f2
--- /dev/null
+++ b/notebooks/3D-point-pillars/pre_process_kitti.py
@@ -0,0 +1,160 @@
+import argparse
+import pdb
+import cv2
+import numpy as np
+import os
+from tqdm import tqdm
+import sys
+CUR = os.path.dirname(os.path.abspath(__file__))
+sys.path.append(CUR)
+
+from pointpillars.utils import read_points, write_points, read_calib, read_label, \
+ write_pickle, remove_outside_points, get_points_num_in_bbox, \
+ points_in_bboxes_v2
+
+
+def judge_difficulty(annotation_dict):
+ truncated = annotation_dict['truncated']
+ occluded = annotation_dict['occluded']
+ bbox = annotation_dict['bbox']
+ height = bbox[:, 3] - bbox[:, 1]
+
+ MIN_HEIGHTS = [40, 25, 25]
+ MAX_OCCLUSION = [0, 1, 2]
+ MAX_TRUNCATION = [0.15, 0.30, 0.50]
+ difficultys = []
+ for h, o, t in zip(height, occluded, truncated):
+ difficulty = -1
+ for i in range(2, -1, -1):
+ if h > MIN_HEIGHTS[i] and o <= MAX_OCCLUSION[i] and t <= MAX_TRUNCATION[i]:
+ difficulty = i
+ difficultys.append(difficulty)
+ return np.array(difficultys, dtype=np.int32)
+
+
+def create_data_info_pkl(data_root, data_type, prefix, label=True, db=False):
+ sep = os.path.sep
+ print(f"Processing {data_type} data..")
+ ids_file = os.path.join(CUR, 'pointpillars', 'dataset', 'ImageSets', f'{data_type}.txt')
+ with open(ids_file, 'r') as f:
+ ids = [id.strip() for id in f.readlines()]
+
+ split = 'training' if label else 'testing'
+
+ kitti_infos_dict = {}
+ if db:
+ kitti_dbinfos_train = {}
+ db_points_saved_path = os.path.join(data_root, f'{prefix}_gt_database')
+ os.makedirs(db_points_saved_path, exist_ok=True)
+ for id in tqdm(ids):
+ cur_info_dict={}
+ img_path = os.path.join(data_root, split, 'image_2', f'{id}.png')
+ lidar_path = os.path.join(data_root, split, 'velodyne', f'{id}.bin')
+ calib_path = os.path.join(data_root, split, 'calib', f'{id}.txt')
+ cur_info_dict['velodyne_path'] = sep.join(lidar_path.split(sep)[-3:])
+
+ img = cv2.imread(img_path)
+ image_shape = img.shape[:2]
+ cur_info_dict['image'] = {
+ 'image_shape': image_shape,
+ 'image_path': sep.join(img_path.split(sep)[-3:]),
+ 'image_idx': int(id),
+ }
+
+ calib_dict = read_calib(calib_path)
+ cur_info_dict['calib'] = calib_dict
+
+ lidar_points = read_points(lidar_path)
+ reduced_lidar_points = remove_outside_points(
+ points=lidar_points,
+ r0_rect=calib_dict['R0_rect'],
+ tr_velo_to_cam=calib_dict['Tr_velo_to_cam'],
+ P2=calib_dict['P2'],
+ image_shape=image_shape)
+ saved_reduced_path = os.path.join(data_root, split, 'velodyne_reduced')
+ os.makedirs(saved_reduced_path, exist_ok=True)
+ saved_reduced_points_name = os.path.join(saved_reduced_path, f'{id}.bin')
+ write_points(reduced_lidar_points, saved_reduced_points_name)
+
+ if label:
+ label_path = os.path.join(data_root, split, 'label_2', f'{id}.txt')
+ annotation_dict = read_label(label_path)
+ annotation_dict['difficulty'] = judge_difficulty(annotation_dict)
+ annotation_dict['num_points_in_gt'] = get_points_num_in_bbox(
+ points=reduced_lidar_points,
+ r0_rect=calib_dict['R0_rect'],
+ tr_velo_to_cam=calib_dict['Tr_velo_to_cam'],
+ dimensions=annotation_dict['dimensions'],
+ location=annotation_dict['location'],
+ rotation_y=annotation_dict['rotation_y'],
+ name=annotation_dict['name'])
+ cur_info_dict['annos'] = annotation_dict
+
+ if db:
+ indices, n_total_bbox, n_valid_bbox, bboxes_lidar, name = \
+ points_in_bboxes_v2(
+ points=lidar_points,
+ r0_rect=calib_dict['R0_rect'].astype(np.float32),
+ tr_velo_to_cam=calib_dict['Tr_velo_to_cam'].astype(np.float32),
+ dimensions=annotation_dict['dimensions'].astype(np.float32),
+ location=annotation_dict['location'].astype(np.float32),
+ rotation_y=annotation_dict['rotation_y'].astype(np.float32),
+ name=annotation_dict['name']
+ )
+ for j in range(n_valid_bbox):
+ db_points = lidar_points[indices[:, j]]
+ db_points[:, :3] -= bboxes_lidar[j, :3]
+ db_points_saved_name = os.path.join(db_points_saved_path, f'{int(id)}_{name[j]}_{j}.bin')
+ write_points(db_points, db_points_saved_name)
+
+ db_info={
+ 'name': name[j],
+ 'path': os.path.join(os.path.basename(db_points_saved_path), f'{int(id)}_{name[j]}_{j}.bin'),
+ 'box3d_lidar': bboxes_lidar[j],
+ 'difficulty': annotation_dict['difficulty'][j],
+ 'num_points_in_gt': len(db_points),
+ }
+ if name[j] not in kitti_dbinfos_train:
+ kitti_dbinfos_train[name[j]] = [db_info]
+ else:
+ kitti_dbinfos_train[name[j]].append(db_info)
+
+ kitti_infos_dict[int(id)] = cur_info_dict
+
+ saved_path = os.path.join(data_root, f'{prefix}_infos_{data_type}.pkl')
+ write_pickle(kitti_infos_dict, saved_path)
+ if db:
+ saved_db_path = os.path.join(data_root, f'{prefix}_dbinfos_train.pkl')
+ write_pickle(kitti_dbinfos_train, saved_db_path)
+ return kitti_infos_dict
+
+
+def main(args):
+ data_root = args.data_root
+ prefix = args.prefix
+
+ ## 1. train: create data infomation pkl file && create reduced point clouds
+ ## && create database(points in gt bbox) for data aumentation
+ kitti_train_infos_dict = create_data_info_pkl(data_root, 'train', prefix, db=True)
+
+ ## 2. val: create data infomation pkl file && create reduced point clouds
+ kitti_val_infos_dict = create_data_info_pkl(data_root, 'val', prefix)
+
+ ## 3. trainval: create data infomation pkl file
+ kitti_trainval_infos_dict = {**kitti_train_infos_dict, **kitti_val_infos_dict}
+ saved_path = os.path.join(data_root, f'{prefix}_infos_trainval.pkl')
+ write_pickle(kitti_trainval_infos_dict, saved_path)
+
+ ## 4. test: create data infomation pkl file && create reduced point clouds
+ kitti_test_infos_dict = create_data_info_pkl(data_root, 'test', prefix, label=False)
+
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser(description='Dataset infomation')
+ parser.add_argument('--data_root', default='/mnt/ssd1/lifa_rdata/det/kitti',
+ help='your data root for kitti')
+ parser.add_argument('--prefix', default='kitti',
+ help='the prefix name for the saved .pkl file')
+ args = parser.parse_args()
+
+ main(args)
\ No newline at end of file
diff --git a/notebooks/3D-point-pillars/pretrained/epoch_160.pth b/notebooks/3D-point-pillars/pretrained/epoch_160.pth
new file mode 100644
index 00000000000..10d95c49a9a
Binary files /dev/null and b/notebooks/3D-point-pillars/pretrained/epoch_160.pth differ
diff --git a/notebooks/3D-point-pillars/pretrained/summary/events.out.tfevents.1650798663.VM-1-6-ubuntu.6731.0 b/notebooks/3D-point-pillars/pretrained/summary/events.out.tfevents.1650798663.VM-1-6-ubuntu.6731.0
new file mode 100644
index 00000000000..f1b5d3d31bb
Binary files /dev/null and b/notebooks/3D-point-pillars/pretrained/summary/events.out.tfevents.1650798663.VM-1-6-ubuntu.6731.0 differ
diff --git a/notebooks/3D-point-pillars/requirements.txt b/notebooks/3D-point-pillars/requirements.txt
new file mode 100644
index 00000000000..cfbe58db7e4
--- /dev/null
+++ b/notebooks/3D-point-pillars/requirements.txt
@@ -0,0 +1,11 @@
+numba==0.62.1
+numpy==2.2.6
+open3d==0.19.0
+opencv-python-headless==4.12.0.88
+PyYAML==6.0.3
+setuptools==80.9.0
+tensorboard==2.20.0
+torch==2.9.0
+openvino==2025.3.0
+tqdm==4.67.1
+onnx==1.19.1
diff --git a/notebooks/3D-point-pillars/setup.py b/notebooks/3D-point-pillars/setup.py
new file mode 100644
index 00000000000..abbb488d122
--- /dev/null
+++ b/notebooks/3D-point-pillars/setup.py
@@ -0,0 +1,58 @@
+import os
+
+from setuptools import setup, find_packages
+from torch.utils.cpp_extension import BuildExtension
+
+def make_extensions():
+ cpu_build = os.environ.get("CPU_BUILD", "0") == "1"
+
+ if cpu_build:
+ print("CPU extension")
+ from torch.utils.cpp_extension import CppExtension
+ return [
+ CppExtension(
+ name='pointpillars.ops.voxel_op',
+ sources=[
+ 'pointpillars/ops/voxelization/voxelization.cpp',
+ 'pointpillars/ops/voxelization/voxelization_cpu.cpp',
+ ],
+ ),
+ CppExtension(
+ name='pointpillars.ops.iou3d_op',
+ sources=[
+ 'pointpillars/ops/iou3d/iou3d.cpp',
+ 'pointpillars/ops/iou3d/iou3d_kernel_cpu.cpp',
+ ],
+ ),
+ ]
+ else: # cuda build
+ print("CUDA extension")
+ from torch.utils.cpp_extension import CUDAExtension
+ return [
+ CUDAExtension(
+ name='pointpillars.ops.voxel_op',
+ sources=[
+ 'pointpillars/ops/voxelization/voxelization.cpp',
+ 'pointpillars/ops/voxelization/voxelization_cpu.cpp',
+ 'pointpillars/ops/voxelization/voxelization_cuda.cu',
+ ],
+ define_macros=[('WITH_CUDA', None)],
+ ),
+ CUDAExtension(
+ name='pointpillars.ops.iou3d_op',
+ sources=[
+ 'pointpillars/ops/iou3d/iou3d.cpp',
+ 'pointpillars/ops/iou3d/iou3d_kernel.cu',
+ ],
+ define_macros=[('WITH_CUDA', None)],
+ ),
+ ]
+
+setup(
+ name='pointpillars',
+ version='0.1',
+ packages=find_packages(),
+ ext_modules=make_extensions(),
+ cmdclass={'build_ext': BuildExtension},
+ zip_safe=False
+)
diff --git a/notebooks/3D-point-pillars/test-e2eOV.py b/notebooks/3D-point-pillars/test-e2eOV.py
new file mode 100644
index 00000000000..b011d52240e
--- /dev/null
+++ b/notebooks/3D-point-pillars/test-e2eOV.py
@@ -0,0 +1,120 @@
+"""
+Test PointPillars OpenVINO model with E2E inference
+Usage: python test_exported_model.py --device cpu --pc_path /workspace/pointpillars/dataset/demo_data/test/000002.bin
+"""
+
+import argparse
+import numpy as np
+import os
+import sys
+from e2eOVInference import E2EOVInference
+
+
+
+def point_range_filter(pts, point_range=[0, -39.68, -3, 69.12, 39.68, 1]):
+ """Filter points within specified range"""
+ flag_x_low = pts[:, 0] > point_range[0]
+ flag_y_low = pts[:, 1] > point_range[1]
+ flag_z_low = pts[:, 2] > point_range[2]
+ flag_x_high = pts[:, 0] < point_range[3]
+ flag_y_high = pts[:, 1] < point_range[4]
+ flag_z_high = pts[:, 2] < point_range[5]
+ keep_mask = flag_x_low & flag_y_low & flag_z_low & flag_x_high & flag_y_high & flag_z_high
+ return pts[keep_mask]
+
+
+def keep_bbox_from_lidar_range(result, pcd_limit_range):
+ """Filter bboxes within specified range"""
+ lidar_bboxes = result['lidar_bboxes']
+ labels = result['labels']
+ scores = result['scores']
+
+ flag1 = lidar_bboxes[:, :3] > pcd_limit_range[:3][None, :]
+ flag2 = lidar_bboxes[:, :3] < pcd_limit_range[3:][None, :]
+ keep_flag = np.all(flag1, axis=-1) & np.all(flag2, axis=-1)
+
+ return {
+ 'lidar_bboxes': lidar_bboxes[keep_flag],
+ 'labels': labels[keep_flag],
+ 'scores': scores[keep_flag]
+ }
+
+def get_pc_from_bin(pc_path):
+ """Load point cloud from .bin file"""
+ pc = np.fromfile(pc_path, dtype=np.float32).reshape(-1, 4)
+ pc = point_range_filter(pc)
+
+ print(f"\n✓ Point cloud loaded: {len(pc)} points (after ROI filtering), shape: {pc.shape}")
+ return pc
+
+def get_pc_from_pcd(pc_path):
+ REPO_ROOT = os.path.join(os.path.dirname(os.path.abspath(__file__)), "PointPillars")
+ if REPO_ROOT not in sys.path:
+ sys.path.insert(0, REPO_ROOT)
+ from pointpillars.dataset.kitti_open3d.utils import read_kitti_pcd
+
+ pts = read_kitti_pcd(pc_path)
+ pc = point_range_filter(pts)
+ print(f"\n✓ Point cloud loaded from PCD: {len(pc)} points (after ROI filtering), shape: {pc.shape}")
+ return pc
+
+def main(args):
+ """Main test function"""
+
+ # Initialize E2E OpenVINO inference engine
+ print(f"Initializing PointPillars OpenVINO inference...")
+ engine = E2EOVInference(
+ config_path=args.config,
+ device=args.device.upper()
+ )
+
+ # Load test point cloud
+ if not os.path.exists(args.pc_path):
+ raise FileNotFoundError(f"Point cloud not found: {args.pc_path}")
+
+ if args.pc_path.endswith('.bin'):
+ pc = get_pc_from_bin(args.pc_path)
+ elif args.pc_path.endswith('.pcd'):
+ pc = get_pc_from_pcd(args.pc_path)
+
+ # Run inference
+ result = engine.infer(pc)
+
+ pcd_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32)
+
+ # Filter results to valid range
+ result_filter = keep_bbox_from_lidar_range(result, pcd_limit_range)
+
+ # Print results
+ lidar_bboxes = result_filter['lidar_bboxes']
+ labels = result_filter['labels']
+ scores = result_filter['scores']
+
+ print(f"\nDetection Results:")
+ print(f"Detected {len(lidar_bboxes)} objects:")
+ for i, (bbox, label, score) in enumerate(zip(lidar_bboxes, labels, scores)):
+ print(f" Object {i}: class={label}, score={score:.3f}")
+
+
+if __name__ == "__main__":
+ current_file_path = os.path.dirname(os.path.abspath(__file__))
+ parser = argparse.ArgumentParser(description='PointPillars OpenVINO E2E Inference Test')
+ parser.add_argument('--device', default='CPU', choices=['CPU', 'GPU'],
+ help='OpenVINO device')
+ parser.add_argument('--config', default=f'{current_file_path}/pretrained/pointpillars_ov_config.json',
+ help='Path to configuration JSON file')
+ parser.add_argument('--pc_path', default=f'{current_file_path}/pointpillars/dataset/demo_data/test/000002.bin',
+ help='Path to point cloud file')
+
+ args = parser.parse_args()
+
+ print("\n" + "="*60)
+ print("PointPillars OpenVINO E2E Inference - Test")
+ print("="*60)
+ print("\nConfiguration:")
+ print(f" device: {args.device}")
+ print(f" config: {args.config}")
+ print(f" pc_path: {args.pc_path}")
+ print("="*60 + "\n")
+
+ main(args)
diff --git a/notebooks/3D-point-pillars/test.py b/notebooks/3D-point-pillars/test.py
new file mode 100644
index 00000000000..ba1525463b1
--- /dev/null
+++ b/notebooks/3D-point-pillars/test.py
@@ -0,0 +1,150 @@
+import argparse
+import cv2
+import numpy as np
+import os
+import torch
+import pdb
+
+from pointpillars.utils import setup_seed, read_points, read_calib, read_label, \
+ keep_bbox_from_image_range, keep_bbox_from_lidar_range, vis_pc, \
+ vis_img_3d, bbox3d2corners_camera, points_camera2image, \
+ bbox_camera2lidar
+from pointpillars.model import PointPillars
+
+
+def point_range_filter(pts, point_range=[0, -39.68, -3, 69.12, 39.68, 1]):
+ '''
+ data_dict: dict(pts, gt_bboxes_3d, gt_labels, gt_names, difficulty)
+ point_range: [x1, y1, z1, x2, y2, z2]
+ '''
+ flag_x_low = pts[:, 0] > point_range[0]
+ flag_y_low = pts[:, 1] > point_range[1]
+ flag_z_low = pts[:, 2] > point_range[2]
+ flag_x_high = pts[:, 0] < point_range[3]
+ flag_y_high = pts[:, 1] < point_range[4]
+ flag_z_high = pts[:, 2] < point_range[5]
+ keep_mask = flag_x_low & flag_y_low & flag_z_low & flag_x_high & flag_y_high & flag_z_high
+ pts = pts[keep_mask]
+ return pts
+
+
+def main(args):
+ CLASSES = {
+ 'Pedestrian': 0,
+ 'Cyclist': 1,
+ 'Car': 2
+ }
+ LABEL2CLASSES = {v:k for k, v in CLASSES.items()}
+ pcd_limit_range = np.array([0, -40, -3, 70.4, 40, 0.0], dtype=np.float32)
+
+ if not args.no_cuda:
+ model = PointPillars(nclasses=len(CLASSES)).cuda()
+ model.load_state_dict(torch.load(args.ckpt))
+ else:
+ model = PointPillars(nclasses=len(CLASSES))
+ model.load_state_dict(
+ torch.load(args.ckpt, map_location=torch.device('cpu')))
+
+ if not os.path.exists(args.pc_path):
+ raise FileNotFoundError
+ pc = read_points(args.pc_path)
+ pc = point_range_filter(pc)
+ pc_torch = torch.from_numpy(pc)
+ if os.path.exists(args.calib_path):
+ calib_info = read_calib(args.calib_path)
+ else:
+ calib_info = None
+
+ if os.path.exists(args.gt_path):
+ gt_label = read_label(args.gt_path)
+ else:
+ gt_label = None
+
+ if os.path.exists(args.img_path):
+ img = cv2.imread(args.img_path, 1)
+ else:
+ img = None
+
+ model.eval()
+ with torch.no_grad():
+ if not args.no_cuda:
+ pc_torch = pc_torch.cuda()
+
+ result_filter = model(batched_pts=[pc_torch],
+ mode='test')[0]
+ if calib_info is not None and img is not None:
+ tr_velo_to_cam = calib_info['Tr_velo_to_cam'].astype(np.float32)
+ r0_rect = calib_info['R0_rect'].astype(np.float32)
+ P2 = calib_info['P2'].astype(np.float32)
+
+ image_shape = img.shape[:2]
+ result_filter = keep_bbox_from_image_range(result_filter, tr_velo_to_cam, r0_rect, P2, image_shape)
+
+ result_filter = keep_bbox_from_lidar_range(result_filter, pcd_limit_range)
+ lidar_bboxes = result_filter['lidar_bboxes']
+ labels, scores = result_filter['labels'], result_filter['scores']
+
+ if not args.headless:
+ vis_pc(pc, bboxes=lidar_bboxes, labels=labels)
+ else:
+ print(f"Detected {len(lidar_bboxes)} objects:")
+ for i, (bbox, label, score) in enumerate(zip(lidar_bboxes, labels, scores)):
+ print(f" Object {i}: class={label}, score={score:.3f}")
+
+ if calib_info is not None and img is not None:
+ bboxes2d, camera_bboxes = result_filter['bboxes2d'], result_filter['camera_bboxes']
+ bboxes_corners = bbox3d2corners_camera(camera_bboxes)
+ image_points = points_camera2image(bboxes_corners, P2)
+ img = vis_img_3d(img, image_points, labels, rt=True)
+
+ if calib_info is not None and gt_label is not None:
+ tr_velo_to_cam = calib_info['Tr_velo_to_cam'].astype(np.float32)
+ r0_rect = calib_info['R0_rect'].astype(np.float32)
+
+ dimensions = gt_label['dimensions']
+ location = gt_label['location']
+ rotation_y = gt_label['rotation_y']
+ gt_labels = np.array([CLASSES.get(item, -1) for item in gt_label['name']])
+ sel = gt_labels != -1
+ gt_labels = gt_labels[sel]
+ bboxes_camera = np.concatenate([location, dimensions, rotation_y[:, None]], axis=-1)
+ gt_lidar_bboxes = bbox_camera2lidar(bboxes_camera, tr_velo_to_cam, r0_rect)
+ bboxes_camera = bboxes_camera[sel]
+ gt_lidar_bboxes = gt_lidar_bboxes[sel]
+
+ gt_labels = [-1] * len(gt_label['name']) # to distinguish between the ground truth and the predictions
+
+ pred_gt_lidar_bboxes = np.concatenate([lidar_bboxes, gt_lidar_bboxes], axis=0)
+ pred_gt_labels = np.concatenate([labels, gt_labels])
+ if not args.headless:
+ vis_pc(pc, pred_gt_lidar_bboxes, labels=pred_gt_labels)
+
+ if img is not None:
+ bboxes_corners = bbox3d2corners_camera(bboxes_camera)
+ image_points = points_camera2image(bboxes_corners, P2)
+ gt_labels = [-1] * len(gt_label['name'])
+ img = vis_img_3d(img, image_points, gt_labels, rt=True)
+
+ if calib_info is not None and img is not None and not args.headless:
+ cv2.imshow(f'{os.path.basename(args.img_path)}-3d bbox', img)
+ cv2.waitKey(0)
+
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser(description='Configuration Parameters')
+ parser.add_argument('--ckpt', default='pretrained/epoch_160.pth', help='your checkpoint for kitti')
+ parser.add_argument('--pc_path', help='your point cloud path')
+ parser.add_argument('--calib_path', default='', help='your calib file path')
+ parser.add_argument('--gt_path', default='', help='your ground truth path')
+ parser.add_argument('--img_path', default='', help='your image path')
+ parser.add_argument('--no_cuda', action='store_true',
+ help='whether to use cuda')
+ parser.add_argument('--headless', action='store_true',
+ help='disable visualization (for Docker/headless environments)')
+ args = parser.parse_args()
+
+ print("Arguments:")
+ for k, v in vars(args).items():
+ print(f"{k}: {v}")
+
+ main(args)
diff --git a/notebooks/3D-point-pillars/train.py b/notebooks/3D-point-pillars/train.py
new file mode 100644
index 00000000000..a4679413c08
--- /dev/null
+++ b/notebooks/3D-point-pillars/train.py
@@ -0,0 +1,214 @@
+import argparse
+import os
+import torch
+from tqdm import tqdm
+import pdb
+
+from pointpillars.utils import setup_seed
+from pointpillars.dataset import Kitti, get_dataloader
+from pointpillars.model import PointPillars
+from pointpillars.loss import Loss
+from torch.utils.tensorboard import SummaryWriter
+
+def save_summary(writer, loss_dict, global_step, tag, lr=None, momentum=None):
+ for k, v in loss_dict.items():
+ writer.add_scalar(f'{tag}/{k}', v, global_step)
+ if lr is not None:
+ writer.add_scalar('lr', lr, global_step)
+ if momentum is not None:
+ writer.add_scalar('momentum', momentum, global_step)
+
+
+def main(args):
+ setup_seed()
+ train_dataset = Kitti(data_root=args.data_root,
+ split='train')
+ val_dataset = Kitti(data_root=args.data_root,
+ split='val')
+ train_dataloader = get_dataloader(dataset=train_dataset,
+ batch_size=args.batch_size,
+ num_workers=args.num_workers,
+ shuffle=True)
+ val_dataloader = get_dataloader(dataset=val_dataset,
+ batch_size=args.batch_size,
+ num_workers=args.num_workers,
+ shuffle=False)
+
+ if not args.no_cuda:
+ pointpillars = PointPillars(nclasses=args.nclasses).cuda()
+ else:
+ pointpillars = PointPillars(nclasses=args.nclasses)
+ loss_func = Loss()
+
+ max_iters = len(train_dataloader) * args.max_epoch
+ init_lr = args.init_lr
+ optimizer = torch.optim.AdamW(params=pointpillars.parameters(),
+ lr=init_lr,
+ betas=(0.95, 0.99),
+ weight_decay=0.01)
+ scheduler = torch.optim.lr_scheduler.OneCycleLR(optimizer,
+ max_lr=init_lr*10,
+ total_steps=max_iters,
+ pct_start=0.4,
+ anneal_strategy='cos',
+ cycle_momentum=True,
+ base_momentum=0.95*0.895,
+ max_momentum=0.95,
+ div_factor=10)
+ saved_logs_path = os.path.join(args.saved_path, 'summary')
+ os.makedirs(saved_logs_path, exist_ok=True)
+ writer = SummaryWriter(saved_logs_path)
+ saved_ckpt_path = os.path.join(args.saved_path, 'checkpoints')
+ os.makedirs(saved_ckpt_path, exist_ok=True)
+
+ for epoch in range(args.max_epoch):
+ print('=' * 20, epoch, '=' * 20)
+ train_step, val_step = 0, 0
+ for i, data_dict in enumerate(tqdm(train_dataloader)):
+ if not args.no_cuda:
+ # move the tensors to the cuda
+ for key in data_dict:
+ for j, item in enumerate(data_dict[key]):
+ if torch.is_tensor(item):
+ data_dict[key][j] = data_dict[key][j].cuda()
+
+ optimizer.zero_grad()
+
+ batched_pts = data_dict['batched_pts']
+ batched_gt_bboxes = data_dict['batched_gt_bboxes']
+ batched_labels = data_dict['batched_labels']
+ batched_difficulty = data_dict['batched_difficulty']
+ bbox_cls_pred, bbox_pred, bbox_dir_cls_pred, anchor_target_dict = \
+ pointpillars(batched_pts=batched_pts,
+ mode='train',
+ batched_gt_bboxes=batched_gt_bboxes,
+ batched_gt_labels=batched_labels)
+
+ bbox_cls_pred = bbox_cls_pred.permute(0, 2, 3, 1).reshape(-1, args.nclasses)
+ bbox_pred = bbox_pred.permute(0, 2, 3, 1).reshape(-1, 7)
+ bbox_dir_cls_pred = bbox_dir_cls_pred.permute(0, 2, 3, 1).reshape(-1, 2)
+
+ batched_bbox_labels = anchor_target_dict['batched_labels'].reshape(-1)
+ batched_label_weights = anchor_target_dict['batched_label_weights'].reshape(-1)
+ batched_bbox_reg = anchor_target_dict['batched_bbox_reg'].reshape(-1, 7)
+ # batched_bbox_reg_weights = anchor_target_dict['batched_bbox_reg_weights'].reshape(-1)
+ batched_dir_labels = anchor_target_dict['batched_dir_labels'].reshape(-1)
+ # batched_dir_labels_weights = anchor_target_dict['batched_dir_labels_weights'].reshape(-1)
+
+ pos_idx = (batched_bbox_labels >= 0) & (batched_bbox_labels < args.nclasses)
+ bbox_pred = bbox_pred[pos_idx]
+ batched_bbox_reg = batched_bbox_reg[pos_idx]
+ # sin(a - b) = sin(a)*cos(b) - cos(a)*sin(b)
+ bbox_pred[:, -1] = torch.sin(bbox_pred[:, -1].clone()) * torch.cos(batched_bbox_reg[:, -1].clone())
+ batched_bbox_reg[:, -1] = torch.cos(bbox_pred[:, -1].clone()) * torch.sin(batched_bbox_reg[:, -1].clone())
+ bbox_dir_cls_pred = bbox_dir_cls_pred[pos_idx]
+ batched_dir_labels = batched_dir_labels[pos_idx]
+
+ num_cls_pos = (batched_bbox_labels < args.nclasses).sum()
+ bbox_cls_pred = bbox_cls_pred[batched_label_weights > 0]
+ batched_bbox_labels[batched_bbox_labels < 0] = args.nclasses
+ batched_bbox_labels = batched_bbox_labels[batched_label_weights > 0]
+
+ loss_dict = loss_func(bbox_cls_pred=bbox_cls_pred,
+ bbox_pred=bbox_pred,
+ bbox_dir_cls_pred=bbox_dir_cls_pred,
+ batched_labels=batched_bbox_labels,
+ num_cls_pos=num_cls_pos,
+ batched_bbox_reg=batched_bbox_reg,
+ batched_dir_labels=batched_dir_labels)
+
+ loss = loss_dict['total_loss']
+ loss.backward()
+ # torch.nn.utils.clip_grad_norm_(pointpillars.parameters(), max_norm=35)
+ optimizer.step()
+ scheduler.step()
+
+ global_step = epoch * len(train_dataloader) + train_step + 1
+
+ if global_step % args.log_freq == 0:
+ save_summary(writer, loss_dict, global_step, 'train',
+ lr=optimizer.param_groups[0]['lr'],
+ momentum=optimizer.param_groups[0]['betas'][0])
+ train_step += 1
+ if (epoch + 1) % args.ckpt_freq_epoch == 0:
+ torch.save(pointpillars.state_dict(), os.path.join(saved_ckpt_path, f'epoch_{epoch+1}.pth'))
+
+ if epoch % 2 == 0:
+ continue
+ pointpillars.eval()
+ with torch.no_grad():
+ for i, data_dict in enumerate(tqdm(val_dataloader)):
+ if not args.no_cuda:
+ # move the tensors to the cuda
+ for key in data_dict:
+ for j, item in enumerate(data_dict[key]):
+ if torch.is_tensor(item):
+ data_dict[key][j] = data_dict[key][j].cuda()
+
+ batched_pts = data_dict['batched_pts']
+ batched_gt_bboxes = data_dict['batched_gt_bboxes']
+ batched_labels = data_dict['batched_labels']
+ batched_difficulty = data_dict['batched_difficulty']
+ bbox_cls_pred, bbox_pred, bbox_dir_cls_pred, anchor_target_dict = \
+ pointpillars(batched_pts=batched_pts,
+ mode='train',
+ batched_gt_bboxes=batched_gt_bboxes,
+ batched_gt_labels=batched_labels)
+
+ bbox_cls_pred = bbox_cls_pred.permute(0, 2, 3, 1).reshape(-1, args.nclasses)
+ bbox_pred = bbox_pred.permute(0, 2, 3, 1).reshape(-1, 7)
+ bbox_dir_cls_pred = bbox_dir_cls_pred.permute(0, 2, 3, 1).reshape(-1, 2)
+
+ batched_bbox_labels = anchor_target_dict['batched_labels'].reshape(-1)
+ batched_label_weights = anchor_target_dict['batched_label_weights'].reshape(-1)
+ batched_bbox_reg = anchor_target_dict['batched_bbox_reg'].reshape(-1, 7)
+ # batched_bbox_reg_weights = anchor_target_dict['batched_bbox_reg_weights'].reshape(-1)
+ batched_dir_labels = anchor_target_dict['batched_dir_labels'].reshape(-1)
+ # batched_dir_labels_weights = anchor_target_dict['batched_dir_labels_weights'].reshape(-1)
+
+ pos_idx = (batched_bbox_labels >= 0) & (batched_bbox_labels < args.nclasses)
+ bbox_pred = bbox_pred[pos_idx]
+ batched_bbox_reg = batched_bbox_reg[pos_idx]
+ # sin(a - b) = sin(a)*cos(b) - cos(a)*sin(b)
+ bbox_pred[:, -1] = torch.sin(bbox_pred[:, -1]) * torch.cos(batched_bbox_reg[:, -1])
+ batched_bbox_reg[:, -1] = torch.cos(bbox_pred[:, -1]) * torch.sin(batched_bbox_reg[:, -1])
+ bbox_dir_cls_pred = bbox_dir_cls_pred[pos_idx]
+ batched_dir_labels = batched_dir_labels[pos_idx]
+
+ num_cls_pos = (batched_bbox_labels < args.nclasses).sum()
+ bbox_cls_pred = bbox_cls_pred[batched_label_weights > 0]
+ batched_bbox_labels[batched_bbox_labels < 0] = args.nclasses
+ batched_bbox_labels = batched_bbox_labels[batched_label_weights > 0]
+
+ loss_dict = loss_func(bbox_cls_pred=bbox_cls_pred,
+ bbox_pred=bbox_pred,
+ bbox_dir_cls_pred=bbox_dir_cls_pred,
+ batched_labels=batched_bbox_labels,
+ num_cls_pos=num_cls_pos,
+ batched_bbox_reg=batched_bbox_reg,
+ batched_dir_labels=batched_dir_labels)
+
+ global_step = epoch * len(val_dataloader) + val_step + 1
+ if global_step % args.log_freq == 0:
+ save_summary(writer, loss_dict, global_step, 'val')
+ val_step += 1
+ pointpillars.train()
+
+
+if __name__ == '__main__':
+ parser = argparse.ArgumentParser(description='Configuration Parameters')
+ parser.add_argument('--data_root', default='/mnt/ssd1/lifa_rdata/det/kitti',
+ help='your data root for kitti')
+ parser.add_argument('--saved_path', default='pillar_logs')
+ parser.add_argument('--batch_size', type=int, default=6)
+ parser.add_argument('--num_workers', type=int, default=4)
+ parser.add_argument('--nclasses', type=int, default=3)
+ parser.add_argument('--init_lr', type=float, default=0.00025)
+ parser.add_argument('--max_epoch', type=int, default=160)
+ parser.add_argument('--log_freq', type=int, default=8)
+ parser.add_argument('--ckpt_freq_epoch', type=int, default=20)
+ parser.add_argument('--no_cuda', action='store_true',
+ help='whether to use cuda')
+ args = parser.parse_args()
+
+ main(args)