mirror of
https://github.com/Ascend/ascend_community_projects.git
synced 2025-09-26 20:01:17 +08:00
2d_lidar
This commit is contained in:
41
2D_LiDAR_Pedestrain_Detection/.gitignore
vendored
Normal file
41
2D_LiDAR_Pedestrain_Detection/.gitignore
vendored
Normal file
@@ -0,0 +1,41 @@
|
||||
*~
|
||||
*__pycache__*
|
||||
*_ext*
|
||||
*.bag
|
||||
*.json
|
||||
*.csv
|
||||
*.cu.o
|
||||
*.DS_Store
|
||||
*.gif
|
||||
*.ipynb_checkpoints
|
||||
*.pkl
|
||||
*.png
|
||||
*.pth
|
||||
*.pyc
|
||||
*.tfevents*
|
||||
*.yml
|
||||
*.yaml
|
||||
*.om
|
||||
*.catkin_workspace
|
||||
*.txt
|
||||
|
||||
.idea/
|
||||
# .vscode/
|
||||
*.egg-info/
|
||||
build/
|
||||
ckpt/
|
||||
ckpts/
|
||||
ckpts
|
||||
data
|
||||
dist/
|
||||
devel/
|
||||
exp_*/
|
||||
experiments
|
||||
logs
|
||||
output/
|
||||
results/
|
||||
result_*/
|
||||
LaserDet/dr_spaam_ros_backup/
|
||||
LaserDet/dr_spaam_ros/build*/
|
||||
LaserDet/dr_spaam_ros/devel*/
|
||||
wandb
|
218
2D_LiDAR_Pedestrain_Detection/LaserDet/dr_spaam_ros/example.rviz
Normal file
218
2D_LiDAR_Pedestrain_Detection/LaserDet/dr_spaam_ros/example.rviz
Normal file
@@ -0,0 +1,218 @@
|
||||
Panels:
|
||||
- Class: rviz/Displays
|
||||
Help Height: 0
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /LaserScan1
|
||||
- /Marker1/Status1
|
||||
Splitter Ratio: 0.6167800426483154
|
||||
Tree Height: 1681
|
||||
- Class: rviz/Selection
|
||||
Name: Selection
|
||||
- Class: rviz/Tool Properties
|
||||
Expanded:
|
||||
- /2D Pose Estimate1
|
||||
- /2D Nav Goal1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: LaserScan
|
||||
Preferences:
|
||||
PromptSaveOnExit: true
|
||||
Toolbars:
|
||||
toolButtonStyle: 2
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.30000001192092896
|
||||
Cell Size: 1
|
||||
Class: rviz/Grid
|
||||
Color: 85; 87; 83
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 2000
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Class: rviz/TF
|
||||
Enabled: true
|
||||
Frame Timeout: 1e+8
|
||||
Frames:
|
||||
All Enabled: false
|
||||
base_chassis_link:
|
||||
Value: true
|
||||
base_link:
|
||||
Value: true
|
||||
left_wheel_link:
|
||||
Value: true
|
||||
m1n6s200_link_1:
|
||||
Value: true
|
||||
m1n6s200_link_2:
|
||||
Value: true
|
||||
m1n6s200_link_3:
|
||||
Value: true
|
||||
m1n6s200_link_4:
|
||||
Value: true
|
||||
m1n6s200_link_5:
|
||||
Value: true
|
||||
m1n6s200_link_6:
|
||||
Value: true
|
||||
m1n6s200_link_base:
|
||||
Value: true
|
||||
m1n6s200_link_finger_1:
|
||||
Value: true
|
||||
m1n6s200_link_finger_2:
|
||||
Value: true
|
||||
odom:
|
||||
Value: true
|
||||
pan_link:
|
||||
Value: true
|
||||
right_wheel_link:
|
||||
Value: true
|
||||
tilt_link:
|
||||
Value: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: true
|
||||
Tree:
|
||||
odom:
|
||||
base_link:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Autocompute Intensity Bounds: true
|
||||
Autocompute Value Bounds:
|
||||
Max Value: 10
|
||||
Min Value: -10
|
||||
Value: true
|
||||
Axis: Z
|
||||
Channel Name: intensity
|
||||
Class: rviz/LaserScan
|
||||
Color: 114; 159; 207
|
||||
Color Transformer: FlatColor
|
||||
Decay Time: 0
|
||||
Enabled: true
|
||||
Invert Rainbow: false
|
||||
Max Color: 255; 255; 255
|
||||
Max Intensity: 4096
|
||||
Min Color: 0; 0; 0
|
||||
Min Intensity: 0
|
||||
Name: LaserScan
|
||||
Position Transformer: XYZ
|
||||
Queue Size: 10
|
||||
Selectable: true
|
||||
Size (Pixels): 5
|
||||
Size (m): 0.10000000149011612
|
||||
Style: Points
|
||||
Topic: /segway/scan_multi
|
||||
Unreliable: false
|
||||
Use Fixed Frame: true
|
||||
Use rainbow: true
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Arrow Length: 1
|
||||
Axes Length: 0.20000000298023224
|
||||
Axes Radius: 0.05000000074505806
|
||||
Class: rviz/PoseArray
|
||||
Color: 52; 101; 164
|
||||
Enabled: false
|
||||
Head Length: 0
|
||||
Head Radius: 0
|
||||
Name: PoseArray
|
||||
Shaft Length: 0.20000000298023224
|
||||
Shaft Radius: 0.20000000298023224
|
||||
Shape: Arrow (3D)
|
||||
Topic: /dr_spaam_detections
|
||||
Unreliable: false
|
||||
Value: false
|
||||
- Class: rviz/Marker
|
||||
Enabled: true
|
||||
Marker Topic: /dr_spaam_rviz
|
||||
Name: Marker
|
||||
Namespaces:
|
||||
dr_spaam_ros: true
|
||||
Queue Size: 100
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 46; 52; 54
|
||||
Default Light: true
|
||||
Fixed Frame: odom
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz/MoveCamera
|
||||
- Class: rviz/Select
|
||||
- Class: rviz/FocusCamera
|
||||
- Class: rviz/Measure
|
||||
- Class: rviz/SetInitialPose
|
||||
Theta std deviation: 0.2617993950843811
|
||||
Topic: /initialpose
|
||||
X std deviation: 0.5
|
||||
Y std deviation: 0.5
|
||||
- Class: rviz/SetGoal
|
||||
Topic: /move_base_simple/goal
|
||||
- Class: rviz/PublishPoint
|
||||
Single click: true
|
||||
Topic: /clicked_point
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Angle: 3.655003786087036
|
||||
Class: rviz/TopDownOrtho
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Scale: 52.93107604980469
|
||||
Target Frame: sick_laser_front
|
||||
Value: TopDownOrtho (rviz)
|
||||
X: 0.7433948516845703
|
||||
Y: 89.31505584716797
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 2049
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: true
|
||||
QMainWindow State: 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
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 3840
|
||||
X: 0
|
||||
Y: 55
|
@@ -0,0 +1,13 @@
|
||||
#!/usr/bin/env python
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
@@ -0,0 +1,493 @@
|
||||
#!/usr/bin/env python
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import time
|
||||
import json
|
||||
import numpy as np
|
||||
import shutil
|
||||
import matplotlib.pyplot as plt
|
||||
from collections import deque
|
||||
import rospy
|
||||
|
||||
from sensor_msgs.msg import LaserScan
|
||||
from geometry_msgs.msg import Point, Pose, PoseArray
|
||||
from visualization_msgs.msg import Marker
|
||||
from std_msgs.msg import Int16
|
||||
|
||||
import os
|
||||
import stat
|
||||
import sys
|
||||
sys.path.append("/home/HwHiAiUser/edge_dev/2D_LiDAR_Pedestrain_Detection/LaserDet")
|
||||
from pprint import pprint
|
||||
pprint(sys.path)
|
||||
from srcs.detector import scans_to_cutout
|
||||
from srcs.utils.precision_recall import eval_internal
|
||||
|
||||
from StreamManagerApi import StreamManagerApi, MxDataInput, MxBufferInput, StringVector
|
||||
from StreamManagerApi import InProtobufVector, MxProtobufIn
|
||||
import MxpiDataType_pb2 as MxpiDataType
|
||||
|
||||
|
||||
FLAGS = os.O_WRONLY | os.O_CREAT
|
||||
MODES = stat.S_IWUSR | stat.S_IRUSR
|
||||
|
||||
|
||||
class LaserDetROS:
|
||||
"""ROS node to detect pedestrian using DROW3 or DR-SPAAM."""
|
||||
|
||||
def __init__(self, pipe_store, timestamps_path, mode=1):
|
||||
|
||||
self.visu = True # False Or True
|
||||
self._seq_name = "rendering"
|
||||
self._bag_id = -1
|
||||
self._anno_id = 0
|
||||
# Set scan params
|
||||
self.conf_thresh = 0.5
|
||||
self.stride = 1
|
||||
self.panoramic_scan = True
|
||||
self.detector_model = os.path.basename(pipe_store).split("_")[0]
|
||||
if self.detector_model == "drow3":
|
||||
self._num_scans = 1
|
||||
else:
|
||||
self._num_scans = 10
|
||||
|
||||
self.ct_kwargs = {
|
||||
"win_width": 1.0,
|
||||
"win_depth": 0.5,
|
||||
"num_ct_pts": 56,
|
||||
"pad_val": 29.99,
|
||||
}
|
||||
|
||||
if mode == 2:
|
||||
self._init()
|
||||
|
||||
self._laser_scans = deque([None] * self._num_scans)
|
||||
self._tested_id = deque([0])
|
||||
|
||||
if "jrdb" in pipe_store or "JRDB" in pipe_store:
|
||||
self._laser_fov_deg = 360
|
||||
bisec_fov_rad = 0.5 * np.deg2rad(self._laser_fov_deg)
|
||||
self._scan_phi = np.linspace(
|
||||
-bisec_fov_rad, bisec_fov_rad, 1091, dtype=np.float32
|
||||
)
|
||||
elif "drow" in pipe_store or "DROW" in pipe_store:
|
||||
self._laser_fov_deg = 225
|
||||
bisec_fov_rad = 0.5 * np.deg2rad(self._laser_fov_deg)
|
||||
self._scan_phi = np.linspace(
|
||||
-bisec_fov_rad, bisec_fov_rad, 450, dtype=np.float32
|
||||
)
|
||||
|
||||
self._timestamps = timestamps_path
|
||||
with open(self._timestamps, "rb") as f:
|
||||
self._ts_frames = json.load(f)["data"]
|
||||
self._mode = mode # 1: eval, 2: display
|
||||
|
||||
# The following belongs to the SDK Process
|
||||
self._stream_manager_api = StreamManagerApi()
|
||||
# init stream manager
|
||||
ret = self._stream_manager_api.InitManager()
|
||||
if ret != 0:
|
||||
print("Failed to init Stream manager, ret=%s" % str(ret))
|
||||
exit()
|
||||
else:
|
||||
print("-----------------创建流管理StreamManager并初始化-----------------")
|
||||
|
||||
# create streams by pipeline config file
|
||||
with open(pipe_store, 'rb') as f:
|
||||
print("-----------------正在读取读取pipeline-----------------")
|
||||
pipeline_str = f.read()
|
||||
print("-----------------成功读取pipeline-----------------")
|
||||
|
||||
_ret = self._stream_manager_api.CreateMultipleStreams(pipeline_str)
|
||||
|
||||
# Print error message
|
||||
if _ret != 0:
|
||||
print(
|
||||
"-----------------Failed to create Stream, ret=%s-----------------" %
|
||||
str(_ret))
|
||||
else:
|
||||
print(
|
||||
"-----------------Create Stream Successfully, ret=%s-----------------" %
|
||||
str(_ret))
|
||||
# Stream name
|
||||
|
||||
self._stream_name = b'detection0'
|
||||
|
||||
self.in_plugin_id = 0
|
||||
tb_dict_list = []
|
||||
dets_xy_accum = {}
|
||||
dets_cls_accum = {}
|
||||
dets_inds_accum = {}
|
||||
gts_xy_accum = {}
|
||||
gts_inds_accum = {}
|
||||
fig_dict = {}
|
||||
|
||||
|
||||
def _init(self):
|
||||
"""
|
||||
@brief Initialize ROS connection.
|
||||
"""
|
||||
# Publisher
|
||||
#topic, queue_size, latch = read_publisher_param("detections")
|
||||
# /dr_spaam_detections, 1, False
|
||||
self._dets_pub = rospy.Publisher(
|
||||
"/laser_det_detections", PoseArray, queue_size=1, latch=False
|
||||
)
|
||||
|
||||
#topic, queue_size, latch = read_publisher_param("rviz")
|
||||
# /dr_spaam_rviz, 1, False
|
||||
self._rviz_pub = rospy.Publisher(
|
||||
"/laser_det_rviz", Marker, queue_size=1, latch=False
|
||||
)
|
||||
|
||||
# Subscriber
|
||||
#topic, queue_size = read_subscriber_param("scan")
|
||||
# /segway/scan_multi, 1
|
||||
|
||||
self._scan_sub = rospy.Subscriber(
|
||||
"/segway/scan_multi", LaserScan, self._scan_callback, queue_size=1
|
||||
)
|
||||
|
||||
|
||||
def __len__(self):
|
||||
return len(self._laser_scans)
|
||||
|
||||
|
||||
def _sigmoid(self, z):
|
||||
return 1.0 / (1.0 + np.exp(-z))
|
||||
|
||||
|
||||
def _rphi_xy_convertor(self, rdius, ang):
|
||||
return rdius * np.cos(ang), rdius * np.sin(ang)
|
||||
|
||||
|
||||
def _can_glob_convertor(self, rdius, ang, dx, dy):
|
||||
tmp_y = rdius + dy
|
||||
tmp_phi = np.arctan2(dx, tmp_y)
|
||||
dets_phi = tmp_phi + ang
|
||||
dets_r = tmp_y / np.cos(tmp_phi)
|
||||
return dets_r, dets_phi
|
||||
|
||||
|
||||
def _nms(
|
||||
self, scan_grid, phi_grid, pred_cls, pred_reg, min_dist=0.5
|
||||
):
|
||||
assert len(pred_cls.shape) == 1
|
||||
|
||||
pred_r, pred_phi = self._can_glob_convertor(
|
||||
scan_grid, phi_grid, pred_reg[:, 0], pred_reg[:, 1]
|
||||
)
|
||||
pred_xs, pred_ys = self._rphi_xy_convertor(pred_r, pred_phi)
|
||||
|
||||
# sort prediction with descending confidence
|
||||
sort_inds = np.argsort(pred_cls)[::-1]
|
||||
|
||||
pred_xs, pred_ys = pred_xs[sort_inds], pred_ys[sort_inds]
|
||||
pred_cls = pred_cls[sort_inds]
|
||||
|
||||
# compute pair-wise distance
|
||||
num_pts = len(scan_grid)
|
||||
xdiff = pred_xs.reshape(num_pts, 1) - pred_xs.reshape(1, num_pts)
|
||||
ydiff = pred_ys.reshape(num_pts, 1) - pred_ys.reshape(1, num_pts)
|
||||
p_dist = np.sqrt(np.square(xdiff) + np.square(ydiff))
|
||||
|
||||
# nms
|
||||
keep = np.ones(num_pts, dtype=np.bool_)
|
||||
instance_mask = np.zeros(num_pts, dtype=np.int32)
|
||||
instance_id = 1
|
||||
for i in range(num_pts):
|
||||
if not keep[i]:
|
||||
continue
|
||||
|
||||
dup_inds = p_dist[i] < min_dist
|
||||
keep[dup_inds] = False
|
||||
keep[i] = True
|
||||
instance_mask[sort_inds[dup_inds]] = instance_id
|
||||
instance_id += 1
|
||||
|
||||
det_xys = np.stack((pred_xs, pred_ys), axis=1)[keep]
|
||||
det_cls = pred_cls[keep]
|
||||
|
||||
return det_xys, det_cls, instance_mask
|
||||
|
||||
|
||||
def _plot_one_frame_beta(
|
||||
self,
|
||||
scan_r,
|
||||
scan_phi,
|
||||
frame_idx,
|
||||
pred_reg=None,
|
||||
dets_msg_poses=None,
|
||||
rviz_msg_points=None,
|
||||
xlim=(-7, 7),
|
||||
ylim=(-7, 7),
|
||||
):
|
||||
fig_handle = plt.figure(figsize=(10, 10))
|
||||
ax_handle = fig_handle.add_subplot(111)
|
||||
ax_handle.grid()
|
||||
|
||||
ax_handle.set_xlim(xlim[0], xlim[1])
|
||||
ax_handle.set_ylim(ylim[0], ylim[1])
|
||||
ax_handle.set_xlabel("x [m]")
|
||||
ax_handle.set_ylabel("y [m]")
|
||||
ax_handle.set_aspect("equal")
|
||||
ax_handle.set_title(f"{frame_idx}")
|
||||
|
||||
# plot scan
|
||||
scan_x, scan_y = self._rphi_xy_convertor(scan_r, scan_phi)
|
||||
ax_handle.scatter(scan_x, scan_y, s=1, c="blue")
|
||||
|
||||
# plot rviz
|
||||
for idx, pt in enumerate(rviz_msg_points):
|
||||
if idx % 2 == 0:
|
||||
start_pt = (pt.x, pt.y)
|
||||
else:
|
||||
end_pt = (pt.x, pt.y)
|
||||
ax_handle.plot(start_pt, end_pt, linewidth=0.25, c="orange")
|
||||
|
||||
# plot regression
|
||||
pred_r, pred_phi = self._can_glob_convertor(
|
||||
scan_r, scan_phi, pred_reg[:, 0], pred_reg[:, 1]
|
||||
)
|
||||
pred_x, pred_y = self._rphi_xy_convertor(pred_r, pred_phi)
|
||||
ax_handle.scatter(pred_x, pred_y, s=1, c="red")
|
||||
|
||||
# plot detection
|
||||
for idx, pos in enumerate(dets_msg_poses):
|
||||
ax_handle.scatter(pos.position.x, pos.position.y,
|
||||
marker="x", s=40, c="black")
|
||||
ax_handle.scatter(pos.position.x, pos.position.y,
|
||||
s=200, facecolors="none", edgecolors="black")
|
||||
|
||||
return fig_handle, ax_handle
|
||||
|
||||
|
||||
def _scan_callback(self, msg):
|
||||
|
||||
self._bag_id += 1
|
||||
|
||||
output_save_dir = os.path.realpath(
|
||||
os.path.join(os.getcwd(), os.path.dirname(__file__)))
|
||||
|
||||
scan = np.array(msg.ranges) # len of msg.ranges: 1091
|
||||
scan[scan == 0.0] = 29.99
|
||||
scan[np.isinf(scan)] = 29.99
|
||||
scan[np.isnan(scan)] = 29.99
|
||||
|
||||
# added-in
|
||||
self._laser_scans.append(scan) # append to the right
|
||||
self._laser_scans.popleft() # pop out from the left
|
||||
|
||||
if self._num_scans > 1:
|
||||
laser_scans = list(filter(lambda x: x is not None, self._laser_scans))
|
||||
else:
|
||||
laser_scans = self._laser_scans
|
||||
scan_index = len(laser_scans)
|
||||
delta_inds = (np.arange(self._num_scans) * self.stride)[::-1]
|
||||
scans_inds = [max(0, scan_index - i) for i in delta_inds]
|
||||
|
||||
scans = np.array([laser_scans[i-1] for i in scans_inds])
|
||||
scans = scans[:, ::-1]
|
||||
laser_input = scans_to_cutout(
|
||||
scans,
|
||||
self._scan_phi,
|
||||
stride=self.stride,
|
||||
win_size=[1.0, 0.5],
|
||||
num_cutout_pts=56,
|
||||
padding_val=29.99,
|
||||
)
|
||||
|
||||
t = time.time()
|
||||
tensor_package_list = MxpiDataType.MxpiTensorPackageList()
|
||||
tensor_package = tensor_package_list.tensorPackageVec.add()
|
||||
tsor = np.expand_dims(laser_input, axis=0).astype('<f4')
|
||||
array_bytes = tsor.tobytes()
|
||||
data_input = MxDataInput()
|
||||
data_input.data = array_bytes
|
||||
tensor_vec = tensor_package.tensorVec.add()
|
||||
tensor_vec.deviceId = 0
|
||||
tensor_vec.memType = 0
|
||||
for i in tsor.shape:
|
||||
tensor_vec.tensorShape.append(i)
|
||||
tensor_vec.dataStr = data_input.data
|
||||
tensor_vec.tensorDataSize = len(array_bytes)
|
||||
|
||||
key = "appsrc{}".format(self.in_plugin_id).encode('utf-8')
|
||||
protobuf_vec = InProtobufVector()
|
||||
protobuf = MxProtobufIn()
|
||||
protobuf.key = key
|
||||
protobuf.type = b'MxTools.MxpiTensorPackageList'
|
||||
protobuf.protobuf = tensor_package_list.SerializeToString()
|
||||
protobuf_vec.push_back(protobuf)
|
||||
|
||||
ret = self._stream_manager_api.SendProtobuf(self._stream_name, self.in_plugin_id, protobuf_vec)
|
||||
|
||||
if ret != 0:
|
||||
print("Failed to send data to stream.")
|
||||
exit()
|
||||
|
||||
key_vec = StringVector()
|
||||
key_vec.push_back(b'mxpi_tensorinfer0')
|
||||
infer_result = self._stream_manager_api.GetProtobuf(self._stream_name, 0, key_vec)
|
||||
|
||||
if infer_result.size() == 0:
|
||||
print("infer_result is null")
|
||||
exit()
|
||||
if infer_result[0].errorCode != 0:
|
||||
print("GetProtobuf error. errorCode=%d" % (
|
||||
infer_result[0].errorCode))
|
||||
exit()
|
||||
result = MxpiDataType.MxpiTensorPackageList()
|
||||
result.ParseFromString(infer_result[0].messageBuf)
|
||||
pred_cls = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[0].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[0].tensorShape))
|
||||
pred_reg = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[1].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[1].tensorShape))
|
||||
prediction_shape = result.tensorPackageVec[0].tensorVec[1].tensorShape
|
||||
|
||||
pred_cls_sigmoid = self._sigmoid(pred_cls.squeeze())
|
||||
dets_xy, dets_cls, inst_mask = self._nms(scans[-1], self._scan_phi, pred_cls_sigmoid, pred_reg.squeeze())
|
||||
print("[DrSpaamROS] End-to-end inference time: %f" % (t - time.time()))
|
||||
'''
|
||||
# dirty fix: save dets to file as roslaunch won't automatively terminate
|
||||
if dets_cls is None:
|
||||
dets_cls = np.ones(len(dets_xy), dtype=np.float32)
|
||||
# occluded for gts only
|
||||
occluded = np.zeros(len(dets_xy), dtype=np.int32)
|
||||
long_str = ""
|
||||
for cls, xy, occ in zip(dets_cls, dets_xy, occluded):
|
||||
long_str += f"Pedestrian 0 {occ} 0 0 0 0 0 0 0 0 0 {xy[0]} {xy[1]} 0 0 {cls}\n"
|
||||
long_str = long_str.strip("\n")
|
||||
txt_name = f"outputs/detections/{self._seq_name}/{str(frame_id).zfill(6)}.txt"
|
||||
det_fname = os.path.join(output_save_dir, txt_name)
|
||||
os.makedirs(os.path.dirname(det_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(det_fname, FLAGS, MODES), "w") as fdo:
|
||||
fdo.write(long_str)
|
||||
'''
|
||||
# confidence threshold (for visulization ONLY)
|
||||
conf_mask = (dets_cls >= self.conf_thresh).reshape(-1)
|
||||
dets_xy = dets_xy[conf_mask]
|
||||
dets_cls = dets_cls[conf_mask]
|
||||
|
||||
# convert to ros msg and publish
|
||||
dets_msg = detections_to_pose_array(dets_xy, dets_cls)
|
||||
dets_msg.header = msg.header
|
||||
self._dets_pub.publish(dets_msg)
|
||||
|
||||
rviz_msg = detections_to_rviz_marker(dets_xy, dets_cls)
|
||||
rviz_msg.header = msg.header
|
||||
self._rviz_pub.publish(rviz_msg)
|
||||
|
||||
# dirty fix: no rendering support ONBOARD !!!
|
||||
if self.visu == False:
|
||||
print(len(dets_msg.poses), len(rviz_msg.points))
|
||||
fig, ax = self._plot_one_frame_beta(scan,
|
||||
self._scan_phi,
|
||||
self._bag_id,
|
||||
pred_reg.squeeze(),
|
||||
dets_msg.poses,
|
||||
rviz_msg.points,
|
||||
)
|
||||
fig_name = f"bags2png/{self._seq_name}/{str(self._bag_id).zfill(6)}.png"
|
||||
fig_file = os.path.join(output_save_dir, fig_name)
|
||||
print("Saving to {}...".format(fig_file))
|
||||
os.makedirs(os.path.dirname(fig_file), exist_ok=True)
|
||||
fig.savefig(fig_file)
|
||||
plt.close(fig)
|
||||
|
||||
|
||||
|
||||
def detections_to_rviz_marker(dets_xy, dets_cls):
|
||||
"""
|
||||
@brief Convert detection to RViz marker msg. Each detection is marked as
|
||||
a circle approximated by line segments.
|
||||
"""
|
||||
msg = Marker()
|
||||
msg.action = Marker.ADD
|
||||
msg.ns = "dr_spaam_ros" # name_space
|
||||
msg.id = 0
|
||||
msg.type = Marker.LINE_LIST
|
||||
|
||||
# set quaternion so that RViz does not give warning
|
||||
msg.pose.orientation.x = 0.0
|
||||
msg.pose.orientation.y = 0.0
|
||||
msg.pose.orientation.z = 0.0
|
||||
msg.pose.orientation.w = 1.0
|
||||
|
||||
msg.scale.x = 0.03 # line width
|
||||
# red color
|
||||
msg.color.r = 1.0
|
||||
msg.color.a = 1.0
|
||||
|
||||
# circle
|
||||
r = 0.4
|
||||
ang = np.linspace(0, 2 * np.pi, 20)
|
||||
xy_offsets = r * np.stack((np.cos(ang), np.sin(ang)), axis=1)
|
||||
|
||||
# to msg
|
||||
for d_xy, d_cls in zip(dets_xy, dets_cls):
|
||||
for i in range(len(xy_offsets) - 1):
|
||||
# start point of a segment
|
||||
p0 = Point()
|
||||
p0.x = d_xy[0] + xy_offsets[i, 0]
|
||||
p0.y = d_xy[1] + xy_offsets[i, 1]
|
||||
p0.z = 0.0
|
||||
msg.points.append(p0)
|
||||
|
||||
# end point
|
||||
p1 = Point()
|
||||
p1.x = d_xy[0] + xy_offsets[i + 1, 0]
|
||||
p1.y = d_xy[1] + xy_offsets[i + 1, 1]
|
||||
p1.z = 0.0
|
||||
msg.points.append(p1)
|
||||
|
||||
return msg
|
||||
|
||||
|
||||
def detections_to_pose_array(dets_xy, dets_cls):
|
||||
pose_array = PoseArray()
|
||||
for d_xy, d_cls in zip(dets_xy, dets_cls):
|
||||
# Detector uses following frame convention:
|
||||
# x forward, y rightward, z downward, phi is angle w.r.t. x-axis
|
||||
p = Pose()
|
||||
p.position.x = d_xy[0]
|
||||
p.position.y = d_xy[1]
|
||||
p.position.z = 0.0
|
||||
pose_array.poses.append(p)
|
||||
|
||||
return pose_array
|
||||
|
||||
|
||||
def read_subscriber_param(name):
|
||||
"""
|
||||
@brief Convenience function to read subscriber parameter.
|
||||
"""
|
||||
topic = rospy.get_param("~subscriber/" + name + "/topic")
|
||||
queue_size = rospy.get_param("~subscriber/" + name + "/queue_size")
|
||||
return topic, queue_size
|
||||
|
||||
|
||||
def read_publisher_param(name):
|
||||
"""
|
||||
@brief Convenience function to read publisher parameter.
|
||||
"""
|
||||
topic = rospy.get_param("~publisher/" + name + "/topic")
|
||||
queue_size = rospy.get_param("~publisher/" + name + "/queue_size")
|
||||
latch = rospy.get_param("~publisher/" + name + "/latch")
|
||||
return topic, queue_size, latch
|
@@ -0,0 +1,4 @@
|
||||
<launch>
|
||||
<node pkg="dr_spaam_ros" type="node.py" name="dr_spaam_ros" output="screen">
|
||||
</node>
|
||||
</launch>
|
@@ -0,0 +1,373 @@
|
||||
#!/usr/bin/env python
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import time
|
||||
import argparse
|
||||
import rospy
|
||||
from dr_spaam_ros import LaserDetROS, detections_to_pose_array, detections_to_rviz_marker
|
||||
# from laser_det_ros import LaserDetROS
|
||||
from sensor_msgs.msg import LaserScan
|
||||
from geometry_msgs.msg import Point, Pose, PoseArray
|
||||
from visualization_msgs.msg import Marker
|
||||
import os
|
||||
import stat
|
||||
import sys
|
||||
sys.path.append("/home/HwHiAiUser/edge_dev/2D_LiDAR_Pedestrain_Detection/LaserDet")
|
||||
from pprint import pprint
|
||||
pprint(sys.path)
|
||||
from srcs.utils.utils import trim_the_scans
|
||||
from srcs.utils.precision_recall import eval_internal
|
||||
import numpy as np
|
||||
import shutil
|
||||
import matplotlib.pyplot as plt
|
||||
|
||||
from StreamManagerApi import StreamManagerApi, MxDataInput, StringVector
|
||||
from StreamManagerApi import InProtobufVector, MxProtobufIn
|
||||
import MxpiDataType_pb2 as MxpiDataType
|
||||
|
||||
|
||||
FLAGS = os.O_WRONLY | os.O_CREAT
|
||||
MODES = stat.S_IWUSR | stat.S_IRUSR
|
||||
|
||||
|
||||
def listener(ros_cls, output_save_dir=None):
|
||||
|
||||
msg = rospy.wait_for_message("/segway/scan_multi", LaserScan, timeout=None)
|
||||
ros_cls._bag_id += 1
|
||||
|
||||
|
||||
scan = np.array(msg.ranges) # len of msg.ranges: 1091
|
||||
#scan[scan == 0.0] = 29.99 # padding valude will be applied to scan_to_cutout
|
||||
#scan[np.isinf(scan)] = 29.99
|
||||
#scan[np.isnan(scan)] = 29.99
|
||||
|
||||
# added-in
|
||||
ros_cls._laser_scans.append(scan) # append to the deque right
|
||||
anno_id = ros_cls._ts_frames[ros_cls._anno_id]['laser_frame']['url'].split('\\')[-1][:-4]
|
||||
frame_id = ros_cls._ts_frames[ros_cls._anno_id]["frame_id"] # detection saved as frame_id
|
||||
#print("await for laser frame:", int(anno_id), "current bag id", ros_cls._bag_id, "frame id in timestamp", frame_id)
|
||||
while int(anno_id) == ros_cls._tested_id[-1]:
|
||||
# if the detection on frame_{anno_id} already exits
|
||||
txt_name = f"outputs/detections/{seq_name}/{str(frame_id).zfill(6)}.txt"
|
||||
dst_fname = os.path.join(output_save_dir, txt_name)
|
||||
src_fname = dst_fname[:-10] + ros_cls._ts_frames[ros_cls._anno_id-1]["frame_id"].zfill(6) + ".txt"
|
||||
shutil.copy(src_fname, dst_fname)
|
||||
ros_cls._anno_id += 1
|
||||
return
|
||||
if ros_cls._bag_id < int(anno_id):
|
||||
ros_cls._laser_scans.popleft() # pop out from the deque left
|
||||
return
|
||||
else:
|
||||
ros_cls._anno_id += 1
|
||||
|
||||
ros_cls._laser_scans.popleft() # pop out from the deque left
|
||||
ros_cls._tested_id.append(int(anno_id))
|
||||
ros_cls._tested_id.popleft()
|
||||
|
||||
if ros_cls._num_scans > 1:
|
||||
laser_scans = list(filter(lambda x: x is not None, ros_cls._laser_scans))
|
||||
else:
|
||||
laser_scans = ros_cls._laser_scans
|
||||
scan_index = len(laser_scans) - (ros_cls._bag_id - ros_cls._tested_id[-1])
|
||||
delta_inds = (np.arange(1, ros_cls._num_scans + 1) * ros_cls.stride)[::-1]
|
||||
scans_inds = [max(0, scan_index - i * ros_cls.stride) for i in delta_inds]
|
||||
scans = np.array([laser_scans[i] for i in scans_inds])
|
||||
|
||||
# equivalent of flipping y axis (inversing laser phi angle)
|
||||
scans = scans[:, ::-1]
|
||||
|
||||
laser_input = trim_the_scans(
|
||||
scans,
|
||||
ros_cls._scan_phi,
|
||||
stride=ros_cls.stride,
|
||||
**ros_cls.ct_kwargs,
|
||||
)
|
||||
|
||||
t = time.time()
|
||||
tensor_package_list = MxpiDataType.MxpiTensorPackageList()
|
||||
tensor_package = tensor_package_list.tensorPackageVec.add()
|
||||
tsor = np.expand_dims(laser_input, axis=0).astype('<f4')
|
||||
array_bytes = tsor.tobytes()
|
||||
data_input = MxDataInput()
|
||||
data_input.data = array_bytes
|
||||
tensor_vec = tensor_package.tensorVec.add()
|
||||
tensor_vec.deviceId = 0
|
||||
tensor_vec.memType = 0
|
||||
for i in tsor.shape:
|
||||
tensor_vec.tensorShape.append(i)
|
||||
tensor_vec.dataStr = data_input.data
|
||||
tensor_vec.tensorDataSize = len(array_bytes)
|
||||
|
||||
key = "appsrc{}".format(ros_cls.in_plugin_id).encode('utf-8')
|
||||
protobuf_vec = InProtobufVector()
|
||||
protobuf = MxProtobufIn()
|
||||
protobuf.key = key
|
||||
protobuf.type = b'MxTools.MxpiTensorPackageList'
|
||||
protobuf.protobuf = tensor_package_list.SerializeToString()
|
||||
protobuf_vec.push_back(protobuf)
|
||||
|
||||
ret = ros_cls._stream_manager_api.SendProtobuf(
|
||||
ros_cls._stream_name, ros_cls.in_plugin_id, protobuf_vec)
|
||||
|
||||
if ret != 0:
|
||||
print("Failed to send data to stream.")
|
||||
exit()
|
||||
|
||||
key_vec = StringVector()
|
||||
key_vec.push_back(b'mxpi_tensorinfer0')
|
||||
infer_result = ros_cls._stream_manager_api.GetProtobuf(ros_cls._stream_name, 0, key_vec)
|
||||
|
||||
if infer_result.size() == 0:
|
||||
print("infer_result is null")
|
||||
exit()
|
||||
if infer_result[0].errorCode != 0:
|
||||
print("GetProtobuf error. errorCode=%d" % (
|
||||
infer_result[0].errorCode))
|
||||
exit()
|
||||
result = MxpiDataType.MxpiTensorPackageList()
|
||||
result.ParseFromString(infer_result[0].messageBuf)
|
||||
pred_cls = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[0].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[0].tensorShape))
|
||||
pred_reg = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[1].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[1].tensorShape))
|
||||
prediction_shape = result.tensorPackageVec[0].tensorVec[1].tensorShape
|
||||
|
||||
pred_cls_sigmoid = ros_cls._sigmoid(pred_cls.squeeze())
|
||||
dets_xy, dets_cls, inst_mask = ros_cls._nms(scans[-1], ros_cls._scan_phi, pred_cls_sigmoid, pred_reg.squeeze())
|
||||
print("[DrSpaamROS] End-to-end inference time: %f" % (t - time.time()))
|
||||
|
||||
# dirty fix: save dets to file as roslaunch won't automatively terminate
|
||||
if dets_cls is None:
|
||||
dets_cls = np.ones(len(dets_xy), dtype=np.float32)
|
||||
# occluded for gts only
|
||||
occluded = np.zeros(len(dets_xy), dtype=np.int32)
|
||||
long_str = ""
|
||||
for category, xy, occ in zip(dets_cls, dets_xy, occluded):
|
||||
long_str += f"Pedestrian 0 {occ} 0 0 0 0 0 0 0 0 0 {xy[0]} {xy[1]} 0 0 {category}\n"
|
||||
long_str = long_str.strip("\n")
|
||||
txt_name = f"outputs/detections/{ros_cls._seq_name}/{str(frame_id).zfill(6)}.txt"
|
||||
det_fname = os.path.join(output_save_dir, txt_name)
|
||||
os.makedirs(os.path.dirname(det_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(det_fname, FLAGS, MODES), "w") as fdo:
|
||||
fdo.write(long_str)
|
||||
|
||||
# convert to ros msg and publish
|
||||
dets_msg = detections_to_pose_array(dets_xy, dets_cls)
|
||||
dets_msg.header = msg.header
|
||||
ros_cls._dets_pub.publish(dets_msg)
|
||||
|
||||
rviz_msg = detections_to_rviz_marker(dets_xy, dets_cls)
|
||||
rviz_msg.header = msg.header
|
||||
ros_cls._rviz_pub.publish(rviz_msg)
|
||||
|
||||
# dirty fix: no rendering support ONBOARD !!!
|
||||
if ros_cls.visu == False:
|
||||
print(len(dets_msg.poses), len(rviz_msg.points))
|
||||
fig, ax = ros_cls._plot_one_frame_beta(scan,
|
||||
ros_cls._scan_phi,
|
||||
ros_cls._bag_id,
|
||||
pred_reg.squeeze(),
|
||||
dets_msg.poses,
|
||||
rviz_msg.points,
|
||||
)
|
||||
fig_name = f"bags2png/{ros_cls._seq_name}/{str(ros_cls._bag_id).zfill(6)}.png"
|
||||
fig_file = os.path.join(output_save_dir, fig_name)
|
||||
print("Saving to {}...".format(fig_file))
|
||||
os.makedirs(os.path.dirname(fig_file), exist_ok=True)
|
||||
fig.savefig(fig_file)
|
||||
plt.close(fig)
|
||||
|
||||
|
||||
def echo(ros_cls, output_save_dir=None):
|
||||
|
||||
anno_id = ros_cls._ts_frames[ros_cls._anno_id]['laser_frame']['url'].split('\\')[-1][:-4]
|
||||
frame_id = ros_cls._ts_frames[ros_cls._anno_id]["frame_id"]
|
||||
|
||||
while int(anno_id) == ros_cls._tested_id[-1]:
|
||||
# if the detection on frame_{anno_id} already exits
|
||||
txt_name = f"outputs/detections/{seq_name}/{str(frame_id).zfill(6)}.txt"
|
||||
dst_fname = os.path.join(output_save_dir, txt_name)
|
||||
src_fname = dst_fname[:-10] + ros_cls._ts_frames[ros_cls._anno_id-1]["frame_id"].zfill(6) + ".txt"
|
||||
shutil.copy(src_fname, dst_fname)
|
||||
ros_cls._anno_id += 1
|
||||
return
|
||||
if ros_cls._bag_id < int(anno_id):
|
||||
ros_cls._laser_scans.popleft() # pop out from the left
|
||||
return
|
||||
else:
|
||||
ros_cls._anno_id += 1
|
||||
|
||||
ros_cls._laser_scans.popleft() # pop out from the left
|
||||
ros_cls._tested_id.append(int(anno_id))
|
||||
ros_cls._tested_id.popleft()
|
||||
|
||||
if ros_cls._num_scans > 1:
|
||||
laser_scans = list(filter(lambda x: x is not None, ros_cls._laser_scans))
|
||||
else:
|
||||
laser_scans = ros_cls._laser_scans
|
||||
scan_index = len(laser_scans) - (ros_cls._bag_id - ros_cls._tested_id[-1])
|
||||
delta_inds = (np.arange(1, ros_cls._num_scans + 1) * ros_cls.stride)[::-1]
|
||||
scans_inds = [max(0, scan_index - i * ros_cls.stride) for i in delta_inds]
|
||||
scans = np.array([laser_scans[i] for i in scans_inds])
|
||||
scans = scans[:, ::-1]
|
||||
|
||||
laser_input = trim_the_scans(
|
||||
scans,
|
||||
ros_cls._scan_phi,
|
||||
stride=ros_cls.stride,
|
||||
**ros_cls.ct_kwargs,
|
||||
)
|
||||
|
||||
t = time.time()
|
||||
tensor_package_list = MxpiDataType.MxpiTensorPackageList()
|
||||
tensor_package = tensor_package_list.tensorPackageVec.add()
|
||||
tsor = np.expand_dims(laser_input, axis=0).astype('<f4')
|
||||
array_bytes = tsor.tobytes()
|
||||
data_input = MxDataInput()
|
||||
data_input.data = array_bytes
|
||||
tensor_vec = tensor_package.tensorVec.add()
|
||||
tensor_vec.deviceId = 0
|
||||
tensor_vec.memType = 0
|
||||
for i in tsor.shape:
|
||||
tensor_vec.tensorShape.append(i)
|
||||
tensor_vec.dataStr = data_input.data
|
||||
tensor_vec.tensorDataSize = len(array_bytes)
|
||||
|
||||
key = "appsrc{}".format(ros_cls.in_plugin_id).encode('utf-8')
|
||||
protobuf_vec = InProtobufVector()
|
||||
protobuf = MxProtobufIn()
|
||||
protobuf.key = key
|
||||
protobuf.type = b'MxTools.MxpiTensorPackageList'
|
||||
protobuf.protobuf = tensor_package_list.SerializeToString()
|
||||
protobuf_vec.push_back(protobuf)
|
||||
|
||||
ret = ros_cls._stream_manager_api.SendProtobuf(ros_cls._stream_name, ros_cls.in_plugin_id, protobuf_vec)
|
||||
|
||||
if ret != 0:
|
||||
print("Failed to send data to stream.")
|
||||
exit()
|
||||
|
||||
key_vec = StringVector()
|
||||
key_vec.push_back(b'mxpi_tensorinfer0')
|
||||
infer_result = ros_cls._stream_manager_api.GetProtobuf(ros_cls._stream_name, 0, key_vec)
|
||||
|
||||
if infer_result.size() == 0:
|
||||
print("infer_result is null")
|
||||
exit()
|
||||
if infer_result[0].errorCode != 0:
|
||||
print("GetProtobuf error. errorCode=%d" % (
|
||||
infer_result[0].errorCode))
|
||||
exit()
|
||||
result = MxpiDataType.MxpiTensorPackageList()
|
||||
result.ParseFromString(infer_result[0].messageBuf)
|
||||
pred_cls = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[0].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[0].tensorShape))
|
||||
pred_reg = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[1].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[1].tensorShape))
|
||||
prediction_shape = result.tensorPackageVec[0].tensorVec[1].tensorShape
|
||||
|
||||
pred_cls_sigmoid = ros_cls._sigmoid(pred_cls.squeeze())
|
||||
dets_xy, dets_cls, inst_mask = ros_cls._nms(scans[-1], ros_cls._scan_phi, pred_cls_sigmoid, pred_reg.squeeze())
|
||||
print("[DrSpaamROS] End-to-end inference time: %f" % (t - time.time()))
|
||||
|
||||
# dirty fix: save dets to file as roslaunch won't automatively terminate
|
||||
if dets_cls is None:
|
||||
dets_cls = np.ones(len(dets_xy), dtype=np.float32)
|
||||
# occluded for gts only
|
||||
occluded = np.zeros(len(dets_xy), dtype=np.int32)
|
||||
long_str = ""
|
||||
for category, xy, occ in zip(dets_cls, dets_xy, occluded):
|
||||
long_str += f"Pedestrian 0 {occ} 0 0 0 0 0 0 0 0 0 {xy[0]} {xy[1]} 0 0 {category}\n"
|
||||
long_str = long_str.strip("\n")
|
||||
txt_name = f"outputs/detections/{ros_cls._seq_name}/{str(frame_id).zfill(6)}.txt"
|
||||
det_fname = os.path.join(output_save_dir, txt_name)
|
||||
os.makedirs(os.path.dirname(det_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(det_fname, FLAGS, MODES), "w") as fdo:
|
||||
fdo.write(long_str)
|
||||
|
||||
|
||||
# dirty fix: no rendering support ONBOARD !!!
|
||||
if ros_cls.visu == False:
|
||||
print(len(dets_msg.poses), len(rviz_msg.points))
|
||||
fig, ax = ros_cls._plot_one_frame_beta(scan,
|
||||
ros_cls._scan_phi,
|
||||
ros_cls._bag_id,
|
||||
pred_reg.squeeze(),
|
||||
dets_msg.poses,
|
||||
rviz_msg.points,
|
||||
)
|
||||
fig_name = f"bags2png/{ros_cls._seq_name}/{str(ros_cls._bag_id).zfill(6)}.png"
|
||||
fig_file = os.path.join(output_save_dir, fig_name)
|
||||
print("Saving to {}...".format(fig_file))
|
||||
os.makedirs(os.path.dirname(fig_file), exist_ok=True)
|
||||
fig.savefig(fig_file)
|
||||
plt.close(fig)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
# init ros node here
|
||||
rospy.init_node("dr_spaam_ros")
|
||||
mode = 1
|
||||
seq_name = "bytes-cafe-2019-02-07_0"
|
||||
timestamps_path = "frames_pc_im_laser.json"
|
||||
pipe_store = "dr_spaam_jrdb_e20.pipeline"
|
||||
|
||||
is_rviz_supported = False
|
||||
# setup callback
|
||||
if mode == 2:
|
||||
try:
|
||||
LaserDetROS(pipe_store, timestamps_path, mode)
|
||||
print("** Node Launched **")
|
||||
except rospy.ROSInterruptException:
|
||||
pass
|
||||
rospy.spin()
|
||||
elif mode == 1:
|
||||
ros_cls = LaserDetROS(pipe_store, timestamps_path, mode)
|
||||
ros_cls._seq_name = seq_name
|
||||
ros_cls.visu = is_rviz_supported
|
||||
ros_cls._dets_pub = rospy.Publisher(
|
||||
"/laser_det_detections", PoseArray, queue_size=1, latch=False
|
||||
)
|
||||
|
||||
ros_cls._rviz_pub = rospy.Publisher(
|
||||
"/laser_det_rviz", Marker, queue_size=1, latch=False
|
||||
)
|
||||
output_save_dir = os.path.realpath(
|
||||
os.path.join(os.getcwd(), os.path.dirname(__file__)))
|
||||
listener_loop = int(ros_cls._ts_frames[-1]['laser_frame']['url'].split('\\')[-1][:-4])
|
||||
while listener_loop >= 0:
|
||||
listener_loop -= 1
|
||||
print("loop", listener_loop)
|
||||
listener(ros_cls, output_save_dir)
|
||||
|
||||
while ros_cls._anno_id < len(ros_cls._ts_frames):
|
||||
print("apre", ros_cls._anno_id)
|
||||
echo(ros_cls, output_save_dir)
|
||||
|
||||
print("Mission completed, please check your output dir and welcome for the next use.")
|
||||
|
||||
|
||||
|
||||
|
@@ -0,0 +1,18 @@
|
||||
<?xml version="1.0"?>
|
||||
<package>
|
||||
<name>dr_spaam_ros</name>
|
||||
<version>1.0.0</version>
|
||||
<description>ROS interface for DR-SPAAM detector</description>
|
||||
|
||||
<maintainer email="jia@vision.rwth-aachen.de">Dan Jia</maintainer>
|
||||
|
||||
<!-- One license tag required, multiple allowed, one license per tag -->
|
||||
<!-- Commonly used license strings: -->
|
||||
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
|
||||
<license>TODO</license>
|
||||
|
||||
<buildtool_depend>catkin</buildtool_depend>
|
||||
<run_depend>rospy</run_depend>
|
||||
<run_depend>geometry_msgs</run_depend>
|
||||
<run_depend>sensor_msgs</run_depend>
|
||||
</package>
|
@@ -0,0 +1,22 @@
|
||||
#!/usr/bin/env python
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from distutils.core import setup
|
||||
from catkin_pkg.python_setup import generate_distutils_setup
|
||||
|
||||
# fetch values from package.xml
|
||||
setup_args = generate_distutils_setup(
|
||||
packages=['dr_spaam_ros'],
|
||||
package_dir={'': 'src'})
|
||||
|
||||
setup(**setup_args)
|
82
2D_LiDAR_Pedestrain_Detection/LaserDet/scripts/det.py
Normal file
82
2D_LiDAR_Pedestrain_Detection/LaserDet/scripts/det.py
Normal file
@@ -0,0 +1,82 @@
|
||||
# Copyright(C) 2021. Huawei Technologies Co.,Ltd. All rights reserved.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
|
||||
import os
|
||||
import argparse
|
||||
from srcs.detector import Detector
|
||||
import numpy as np
|
||||
import onnx
|
||||
import torch
|
||||
|
||||
|
||||
def main(ckpt_path, datset_name, model_name, panoramic, num_pts, num_scans, onnx_name):
|
||||
detector = Detector(
|
||||
ckpt_path,
|
||||
dataset=datset_name, # DROW Or JRDB
|
||||
model=model_name, # DROW3 Or DR-SPAAM
|
||||
gpu=True, # Use GPU
|
||||
stride=1, # Optionally downsample scan for faster inference
|
||||
panoramic_scan=panoramic # Set to True if the scan covers 360 degree
|
||||
)
|
||||
# tell the detector field of view of the LiDAR
|
||||
|
||||
|
||||
scan = np.random.rand(int(num_pts)) # 450 Or 1091
|
||||
scans = np.array([scan for i in range(num_scans)]) # 1 Or 10
|
||||
torch.onnx.export(detector.model,
|
||||
detector.return_data(scans),
|
||||
onnx_name,
|
||||
opset_version=11,
|
||||
verbose=True,
|
||||
export_params=True)
|
||||
|
||||
|
||||
print("Hello onnx")
|
||||
|
||||
if __name__ == "__main__":
|
||||
parser = argparse.ArgumentParser(description="arg parser")
|
||||
parser.add_argument("--ckpt_path",
|
||||
type=str,
|
||||
required=True,
|
||||
help="checkpoints directory.")
|
||||
args = parser.parse_args()
|
||||
main(os.path.join(args.ckpt_path, "drow_e40.pth"),
|
||||
"DROW",
|
||||
"DROW3",
|
||||
False,
|
||||
450,
|
||||
1,
|
||||
"drow3_e40.onnx")
|
||||
main(os.path.join(args.ckpt_path, "dr_spaam_e40.pth"),
|
||||
"DROW",
|
||||
"DR-SPAAM",
|
||||
False,
|
||||
450,
|
||||
10,
|
||||
"dr_spaam_e40.onnx")
|
||||
main(os.path.join(args.ckpt_path, "ckpt_jrdb_ann_ft_drow3_e40.pth"),
|
||||
"JRDB",
|
||||
"DROW3",
|
||||
True,
|
||||
1091,
|
||||
1,
|
||||
"drow3_jrdb_e40.onnx")
|
||||
main(os.path.join(args.ckpt_path, "ckpt_jrdb_ann_ft_dr_spaam_e20.pth"),
|
||||
"JRDB",
|
||||
"DR-SPAAM",
|
||||
True,
|
||||
1091,
|
||||
10,
|
||||
"dr_spaam_jrdb_e20.onnx")
|
@@ -0,0 +1,24 @@
|
||||
#!/bin/bash
|
||||
# Copyright(C) 2021. Huawei Technologies Co.,Ltd. All rights reserved.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
export install_path=/usr/local/Ascend/ascend-toolkit/latest
|
||||
export PATH=/usr/local/python3.7.5/bin:${install_path}/atc/ccec_compiler/bin:${install_path}/atc/bin:$PATH
|
||||
export PYTHONPATH=${install_path}/atc/python/site-packages:${install_path}/atc/python/site-packages/auto_tune.egg/auto_tune:${install_path}/atc/python/site-packages/schedule_search.egg:$PYTHONPATH
|
||||
export LD_LIBRARY_PATH=${install_path}/atc/lib64:$LD_LIBRARY_PATH
|
||||
export ASCEND_OPP_PATH=${install_path}/opp
|
||||
|
||||
atc --model=$1/drow3_drow_e40.onnx --framework=5 --output=drow3_drow_e40 -soc_version=Ascend310
|
||||
atc --model=$1/dr_spaam_drow_e40.onnx --framework=5 --output=dr_spaam_drow_e40 -soc_version=Ascend310
|
||||
atc --model=$1/drow3_jrdb_e40.onnx --framework=5 --output=drow3_jrdb_e40 -soc_version=Ascend310
|
||||
atc --model=$1/dr_spaam_jrdb_e20.onnx --framework=5 --output=dr_spaam_jrdb_e20 -soc_version=Ascend310
|
@@ -0,0 +1,151 @@
|
||||
# Copyright(C) 2021. Huawei Technologies Co.,Ltd. All rights reserved.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import json
|
||||
import os
|
||||
import stat
|
||||
import shutil
|
||||
from collections import defaultdict
|
||||
import numpy as np
|
||||
import rosbag as rb
|
||||
|
||||
FLAGS = os.O_WRONLY | os.O_CREAT
|
||||
MODES = stat.S_IWUSR | stat.S_IRUSR
|
||||
# Set root dir to JRDB
|
||||
_JRDB_DIR = "./dataset/JRDB"
|
||||
|
||||
|
||||
def bag_to_txt(split):
|
||||
# .bag from rosbag to .txt for lasers
|
||||
jrdb_dir = os.path.join(_JRDB_DIR, split + "_dataset")
|
||||
|
||||
timestamps_dir = os.path.join(jrdb_dir, "timestamps")
|
||||
rosbag_dir = timestamps_dir.replace("timestamps", "rosbags")
|
||||
to_laser = timestamps_dir.replace("timestamps", "laser")
|
||||
seq_names = os.listdir(timestamps_dir)
|
||||
|
||||
|
||||
if os.path.exists(to_laser):
|
||||
shutil.rmtree(to_laser)
|
||||
os.mkdir(to_laser)
|
||||
|
||||
for idx, seq_name in enumerate(seq_names):
|
||||
seq_laser_dir = os.path.join(to_laser, seq_name)
|
||||
os.mkdir(seq_laser_dir)
|
||||
|
||||
ros_bag = rb.Bag(os.path.join(rosbag_dir, seq_name + ".bag"))
|
||||
|
||||
# unroll your laser messages
|
||||
timestamp_list = []
|
||||
for cnter, (_, msg, timer) in enumerate(
|
||||
ros_bag.read_messages(topics=["segway/scan_multi"])
|
||||
):
|
||||
|
||||
laser_file = str(cnter).zfill(6) + ".txt"
|
||||
np.savetxt(
|
||||
os.path.join(seq_laser_dir, laser_file),
|
||||
np.array(msg.ranges),
|
||||
newline=" "
|
||||
)
|
||||
|
||||
timestamp_list.append(timer.to_sec())
|
||||
|
||||
np.savetxt(
|
||||
os.path.join(seq_laser_dir, "timestamps.txt"),
|
||||
np.array(timestamp_list),
|
||||
newline=" ",
|
||||
)
|
||||
|
||||
ros_bag.close()
|
||||
|
||||
|
||||
def synchronize_pcl_img_laser(split):
|
||||
seq_names = os.listdir(
|
||||
os.path.join(_JRDB_DIR, split + "_dataset", "timestamps")
|
||||
)
|
||||
for idx, seq_name in enumerate(seq_names):
|
||||
jrdb_dir = os.path.join(_JRDB_DIR, split + "_dataset")
|
||||
|
||||
timestamps_dir = os.path.join(jrdb_dir, "timestamps", seq_name)
|
||||
lasers_dir = timestamps_dir.replace("timestamps", "lasers")
|
||||
|
||||
# loading pointcloud frames
|
||||
with open(timestamps_dir+"/"+"frames_pc.json", "r") as f:
|
||||
pc_data_load = json.load(f)["data"]
|
||||
# loading image frames
|
||||
with open(timestamps_dir+"/"+"frames_img.json", "r") as f:
|
||||
im_data_load = json.load(f)["data"]
|
||||
|
||||
# matching pc and im frame
|
||||
pc_tim = np.array([float(f["timestamp"]) for f in pc_data_load]).reshape(-1, 1)
|
||||
im_tim = np.array([float(f["timestamp"]) for f in im_data_load]).reshape(1, -1)
|
||||
|
||||
p_i_inds = np.abs(pc_tim - im_tim).argmin(axis=1)
|
||||
|
||||
# matching pc and laser
|
||||
laser_tim = np.loadtxt(
|
||||
os.path.join(lasers_dir, "timestamps.txt"), dtype=np.float64
|
||||
)
|
||||
|
||||
p_l_inds = np.abs(pc_tim - laser_tim.reshape(1, -1)).argmin(axis=1)
|
||||
|
||||
# create a merged frame dict
|
||||
frames_collect = []
|
||||
for i, pc_frame in enumerate(pc_data_load):
|
||||
merged_frame = defaultdict({
|
||||
"pc_frame": pc_data_load[i],
|
||||
"im_frame": im_data_load[p_i_inds[i]],
|
||||
"laser_frame": {
|
||||
"url": os.path.join(
|
||||
"laser",
|
||||
seq_name,
|
||||
str(p_l_inds[i]).zfill(6) + ".txt",
|
||||
),
|
||||
"name": "laser_combined",
|
||||
"timestamp": laser_tim[p_l_inds[i]],
|
||||
},
|
||||
"timestamp": pc_data_load[i]["timestamp"],
|
||||
"frame_id": pc_data_load[i]["frame_id"],
|
||||
})
|
||||
|
||||
# correct file url for pc and im
|
||||
for pc_dict in merged_frame["pc_frame"]["pointclouds"]:
|
||||
f_name = os.path.basename(pc_dict["url"])
|
||||
pc_dict["url"] = os.path.join(
|
||||
"pointclouds", pc_dict["name"], seq_name, f_name
|
||||
)
|
||||
|
||||
for im_dict in merged_frame["im_frame"]["cameras"]:
|
||||
f_name = os.path.basename(im_dict["url"])
|
||||
cam_name = (
|
||||
"image_stitched"
|
||||
if im_dict["name"] == "stitched_image0"
|
||||
else im_dict["name"][:-1] + "_" + im_dict["name"][-1]
|
||||
)
|
||||
im_dict["url"] = os.path.join("images", cam_name, seq_name, f_name)
|
||||
|
||||
frames_collect.append(merged_frame)
|
||||
|
||||
# write to file
|
||||
write_json = {"data": frames_collect}
|
||||
json_file = os.path.join(timestamps_dir, "frames_pc_im_laser.json")
|
||||
with os.fdopen(os.open(json_file, FLAGS, MODES), "w") as fp:
|
||||
json.dump(write_json, fp)
|
||||
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
print("Setting up JRDB dataset...")
|
||||
for spl in ["train", "test"]:
|
||||
bag_to_txt(spl)
|
||||
synchronize_pcl_img_laser(spl)
|
12
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/__init__.py
Normal file
12
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/__init__.py
Normal file
@@ -0,0 +1,12 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
@@ -0,0 +1,14 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from .drow_handle import DROWv2Handle
|
||||
from .jrdb_handle import JRDBv1Handle
|
@@ -0,0 +1,125 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from glob import glob
|
||||
import os
|
||||
import json
|
||||
import numpy as np
|
||||
|
||||
|
||||
__all__ = ["DROWv2Handle"]
|
||||
|
||||
|
||||
class DROWv2Handle:
|
||||
def __init__(self, split, data_cfg):
|
||||
assert split in ["train", "val", "test",
|
||||
"test_nano", "test_single",
|
||||
"train_nano", "train_single"], f'Invalid split "{split}"'
|
||||
|
||||
self.__n_scans = data_cfg["num_scans"]
|
||||
self.__scan_stride = data_cfg["scan_stride"]
|
||||
|
||||
if len(data_cfg["data_dir"]) > 1 and isinstance(data_cfg["data_dir"], str) is not True:
|
||||
drow_path = os.path.abspath(os.path.expanduser(data_cfg["data_dir"][0]))
|
||||
self.seq_names = [os.path.join(drow_path, split.split("_")[0], data_cfg["data_dir"][1])[:-4]]
|
||||
print("***", data_cfg["data_dir"], drow_path, self.seq_names)
|
||||
else:
|
||||
drow_path = os.path.abspath(os.path.expanduser(data_cfg["data_dir"]))
|
||||
self.seq_names = [f[:-4] for f in glob(os.path.join(drow_path, split, "*.csv"))]
|
||||
|
||||
# preload all annotations
|
||||
self.dets_seq_wc, self.wcs, self.was, self.wps = list(zip(
|
||||
*map(lambda f: self._preload(f), self.seq_names)
|
||||
))
|
||||
|
||||
# look-up list to convert an index to sequence index and annotation index
|
||||
self.__seq_inds_inline = []
|
||||
self.__det_inds_inline = []
|
||||
for seq_index, det_ns in enumerate(self.dets_seq_wc):
|
||||
self.__seq_inds_inline += [seq_index] * len(det_ns)
|
||||
self.__det_inds_inline += range(len(det_ns))
|
||||
|
||||
# placeholder for scans, which will be preload on the fly
|
||||
self.seq_len = len(self.seq_names)
|
||||
self.scans_seq_no = [None] * self.seq_len
|
||||
self.scans_seq_t = [None] * self.seq_len
|
||||
self.scans_seq_dist = [None] * self.seq_len
|
||||
|
||||
# placeholder for mapping from detection index to scan index
|
||||
self.__did2sid = [None] * self.seq_len
|
||||
|
||||
# load the scan sequence into memory if it has not been loaded
|
||||
for seq_index, s in enumerate(self.seq_names):
|
||||
if self.scans_seq_dist[seq_index] is None:
|
||||
self._get_scan_seq(seq_index)
|
||||
|
||||
|
||||
def __len__(self):
|
||||
return len(self.__det_inds_inline)
|
||||
|
||||
|
||||
def __getitem__(self, idx):
|
||||
# find matching seq_index, det_index, and scan_index
|
||||
seq_index = self.__seq_inds_inline[idx]
|
||||
det_index = self.__det_inds_inline[idx]
|
||||
scan_index = self.__did2sid[seq_index][det_index]
|
||||
|
||||
drow_rtn = {
|
||||
"idx": idx,
|
||||
"dets_wc": self.wcs[seq_index][det_index],
|
||||
"dets_wa": self.was[seq_index][det_index],
|
||||
"dets_wp": self.wps[seq_index][det_index],
|
||||
}
|
||||
|
||||
# load sequential scans up to the current one (array[frame, point])
|
||||
delta_inds = (np.arange(self.__n_scans) * self.__scan_stride)[::-1]
|
||||
scans_inds = [max(0, scan_index - i) for i in delta_inds]
|
||||
drow_rtn["scans"] = np.array([self.scans_seq_dist[seq_index][i] for i in scans_inds])
|
||||
drow_rtn["scans_ind"] = scans_inds
|
||||
laser_fov = (450 - 1) * np.radians(0.5)
|
||||
drow_rtn["scan_phi"] = np.linspace(-laser_fov * 0.5, laser_fov * 0.5, 450)
|
||||
|
||||
return drow_rtn
|
||||
|
||||
|
||||
@classmethod
|
||||
def _preload(self, seq_name):
|
||||
def get_f(f_name):
|
||||
seqs, dets = [], []
|
||||
with open(f_name) as f:
|
||||
for line in f:
|
||||
seq, tail = line.split(",", 1)
|
||||
seqs.append(int(seq))
|
||||
dets.append(json.loads(tail))
|
||||
return seqs, dets
|
||||
|
||||
seq_wc, wcs = get_f(seq_name + ".wc") # [[]*N]
|
||||
seq_wa, was = get_f(seq_name + ".wa") # [[]*N]
|
||||
seq_wp, wps = get_f(seq_name + ".wp") # if not empty
|
||||
assert all(wc == wa == wp for wc, wa, wp in zip(seq_wc, seq_wa, seq_wp))
|
||||
|
||||
return [np.array(seq_wc), wcs, was, wps]
|
||||
|
||||
|
||||
def _get_scan_seq(self, seq_index):
|
||||
drow_data = np.genfromtxt(self.seq_names[seq_index] + ".csv", delimiter=",")
|
||||
self.scans_seq_no[seq_index] = drow_data[:, 0].astype(np.uint32)
|
||||
self.scans_seq_t[seq_index] = drow_data[:, 1].astype(np.float32)
|
||||
self.scans_seq_dist[seq_index] = drow_data[:, 2:].astype(np.float32)
|
||||
|
||||
is_ = 0
|
||||
id2is = []
|
||||
for det_ns in self.dets_seq_wc[seq_index]:
|
||||
while self.scans_seq_no[seq_index][is_] != det_ns:
|
||||
is_ += 1
|
||||
id2is.append(is_)
|
||||
self.__did2sid[seq_index] = id2is
|
@@ -0,0 +1,219 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import copy
|
||||
import os
|
||||
import json
|
||||
import cv2
|
||||
import numpy as np
|
||||
|
||||
|
||||
# Force the dataloader to load only one sample, in which case the network should
|
||||
# fit perfectly.
|
||||
# Pointcloud and image is only needed for visualization. Turn off for fast dataloading
|
||||
|
||||
__all__ = ["JRDBv1Handle"]
|
||||
|
||||
|
||||
class JRDBv1Handle:
|
||||
def __init__(self, split, cfg, sequences=None, exclude_sequences=None):
|
||||
|
||||
self.__num_scans = cfg["num_scans"]
|
||||
self.__scan_stride = cfg["scan_stride"]
|
||||
|
||||
data_path = os.path.abspath(os.path.expanduser(cfg["data_dir"]))
|
||||
data_path = (
|
||||
os.path.join(data_path, "train_dataset")
|
||||
if split == "train" or split == "val"
|
||||
else os.path.join(data_path, "test_dataset")
|
||||
)
|
||||
print("JRDB data_path", cfg["data_dir"], data_path)
|
||||
self.data_path = data_path
|
||||
self.timestamp_path = os.path.join(data_path, "timestamps")
|
||||
self.pc_label_path = os.path.join(data_path, "labels", "labels_3d")
|
||||
self.im_label_path = os.path.join(data_path, "labels", "labels_2d_stitched")
|
||||
|
||||
if sequences is not None:
|
||||
seq_names = sequences
|
||||
else:
|
||||
seq_names = os.listdir(self.timestamp_path)
|
||||
# NOTE it is important to sort the return of os.listdir, since its order
|
||||
# changes for different file system.
|
||||
seq_names.sort()
|
||||
|
||||
if exclude_sequences is not None:
|
||||
seq_names = [s for s in seq_names if s not in exclude_sequences]
|
||||
|
||||
self.seq_names = seq_names
|
||||
|
||||
self.seq_handle = []
|
||||
self._seq_init_start = [0]
|
||||
self.__seq_inds_inline = []
|
||||
self.__frame_inds_inline = []
|
||||
for seq_idx, seq_name in enumerate(self.seq_names):
|
||||
self.seq_handle.append(_SequenceHandle(self.data_path, seq_name))
|
||||
|
||||
# build a flat index for all sequences and frames
|
||||
seq_len = len(self.seq_handle[-1])
|
||||
self.__seq_inds_inline += seq_len * [seq_idx]
|
||||
self.__frame_inds_inline += range(seq_len)
|
||||
|
||||
self._seq_init_start.append(
|
||||
self._seq_init_start[-1] + seq_len
|
||||
)
|
||||
|
||||
def __len__(self):
|
||||
return len(self.__frame_inds_inline)
|
||||
|
||||
def __getitem__(self, idx):
|
||||
idx_sq = self.__seq_inds_inline[idx]
|
||||
idx_fr = self.__frame_inds_inline[idx]
|
||||
handle_ind = self.seq_handle[idx_sq][idx_fr]
|
||||
get_frame_dict = handle_ind.frame
|
||||
|
||||
pc_data = {}
|
||||
im_data = {}
|
||||
for pc_dict in get_frame_dict["pc_frame"]["pointclouds"]: # 3D annotation is not supported at this moment
|
||||
pc_data[pc_dict["name"]] = 0
|
||||
|
||||
for im_dict in get_frame_dict["im_frame"]["cameras"]:
|
||||
im_data[im_dict["name"]] = cv2.cvtColor(cv2.imread(os.path.join(self.data_path,
|
||||
im_dict["url"].replace("\\", "/")),
|
||||
cv2.IMREAD_COLOR), cv2.COLOR_RGB2BGR)
|
||||
|
||||
laser_data = self._load_consecutive_lasers(get_frame_dict["laser_frame"]["url"].replace("\\", "/"))
|
||||
laser_grid = np.linspace(-np.pi, np.pi, laser_data.shape[1], dtype=np.float32)
|
||||
laser_z = -0.5 * np.ones(laser_data.shape[1], dtype=np.float32)
|
||||
get_frame_dict.update(
|
||||
{
|
||||
"frame_id": int(get_frame_dict["frame_id"]),
|
||||
"sequence": self.seq_handle[idx_sq].sequence,
|
||||
"first_frame": idx_fr == 0,
|
||||
"idx": idx,
|
||||
"pc_data": pc_data,
|
||||
"im_data": im_data,
|
||||
"laser_data": laser_data,
|
||||
"pc_anns": handle_ind.pc_anns,
|
||||
"im_anns": handle_ind.img_anns,
|
||||
"im_dets": handle_ind.img_dets,
|
||||
"laser_grid": laser_grid,
|
||||
"laser_z": laser_z,
|
||||
}
|
||||
)
|
||||
return get_frame_dict
|
||||
|
||||
@property
|
||||
def seq_init_start(self):
|
||||
return copy.deepcopy(self._seq_init_start)
|
||||
|
||||
|
||||
def _load_consecutive_lasers(self, scan_url):
|
||||
"""Load current and previous consecutive laser scans.
|
||||
|
||||
Args:
|
||||
url (str): file url of the current scan
|
||||
|
||||
Returns:
|
||||
pc (np.ndarray[self.num_scan, N]): Forward in time with increasing
|
||||
row index, i.e. the latest scan is pc[-1]
|
||||
"""
|
||||
scan_url = scan_url.replace("\\", "/")
|
||||
current_frame_idx = int(os.path.basename(scan_url).split(".")[0])
|
||||
frames_list = []
|
||||
for del_idx in range(self.__num_scans, 0, -1):
|
||||
frame_idx = max(0, current_frame_idx - del_idx * self.__scan_stride)
|
||||
laser_url = os.path.join(os.path.dirname(scan_url), str(frame_idx).zfill(6) + ".txt").replace("\\", "/")
|
||||
laser_loaded = np.loadtxt(os.path.join(self.data_path, laser_url), dtype=np.float32)
|
||||
frames_list.append(laser_loaded)
|
||||
|
||||
return np.stack(frames_list, axis=0)
|
||||
|
||||
|
||||
class _FrameHandle:
|
||||
def __init__(self, frame, pc_anns, img_anns, img_dets):
|
||||
self.frame = frame
|
||||
self.pc_anns = pc_anns
|
||||
self.img_anns = img_anns
|
||||
self.img_dets = img_dets
|
||||
|
||||
|
||||
class _SequenceHandle:
|
||||
def __init__(self, data_path, sequence):
|
||||
self.sequence = sequence
|
||||
|
||||
# load frames of the sequence
|
||||
fname = os.path.join(data_path,
|
||||
"timestamps",
|
||||
self.sequence,
|
||||
"frames_pc_im_laser.json")
|
||||
with open(fname, "r") as f:
|
||||
self.frames = json.load(f)["data"]
|
||||
|
||||
# load 3D annotation pointcloud
|
||||
pc_fname = os.path.join(data_path,
|
||||
"labels",
|
||||
"labels_3d",
|
||||
f"{self.sequence}.json")
|
||||
with open(pc_fname, "r") as f:
|
||||
self.pc_labels = json.load(f)["labels"]
|
||||
|
||||
# load 2D annotation
|
||||
im_label_fname = os.path.join(data_path,
|
||||
"labels",
|
||||
"labels_2d_stitched",
|
||||
f"{self.sequence}.json")
|
||||
with open(im_label_fname, "r") as f:
|
||||
self.im_labels = json.load(f)["labels"]
|
||||
|
||||
# load 2D detection
|
||||
im_det_fname = os.path.join(data_path,
|
||||
"detections",
|
||||
"detections_2d_stitched",
|
||||
f"{self.sequence}.json")
|
||||
with open(im_det_fname, "r") as f:
|
||||
self.im_dets = json.load(f)["detections"]
|
||||
|
||||
# find out which frames has 3D annotation
|
||||
self.frames_labeled = []
|
||||
for frame in self.frames:
|
||||
pc_file = os.path.basename(frame["pc_frame"]["pointclouds"][0]["url"].replace("\\", "/"))
|
||||
|
||||
if pc_file in self.pc_labels:
|
||||
self.frames_labeled.append(frame)
|
||||
|
||||
self.jrdb_frames = (
|
||||
self.frames_labeled
|
||||
)
|
||||
|
||||
|
||||
def __len__(self):
|
||||
return len(self.jrdb_frames)
|
||||
|
||||
def __getitem__(self, idx):
|
||||
# NOTE It's important to use a copy as the return dict, otherwise the
|
||||
# original dict in the data handle will be corrupted
|
||||
jrdb_frame = copy.deepcopy(self.jrdb_frames[idx])
|
||||
|
||||
if self._is_unlabeled_frames:
|
||||
frame_handle = _FrameHandle(jrdb_frame, [], [], [])
|
||||
return frame_handle # frame, [], [], []
|
||||
|
||||
pc_load = os.path.basename(jrdb_frame["pc_frame"]["pointclouds"][0]["url"].replace("\\", "/"))
|
||||
pc_anns = copy.deepcopy(self.pc_labels[pc_load])
|
||||
|
||||
img_file = os.path.basename(jrdb_frame["im_frame"]["cameras"][0]["url"].replace("\\", "/"))
|
||||
img_anns = copy.deepcopy(self.im_labels[img_file])
|
||||
img_dets = copy.deepcopy(self.im_dets[img_file])
|
||||
|
||||
frame_handle = _FrameHandle(jrdb_frame, pc_anns, img_anns, img_dets)
|
||||
|
||||
return frame_handle
|
@@ -0,0 +1,15 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from .builder import get_dataloader
|
||||
from .drow_dataset import DROWDataset
|
||||
from .jrdb_dataset import JRDBDataset
|
@@ -0,0 +1,71 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from torch.utils.data import DataLoader
|
||||
|
||||
_JRDB_SPLIT = {
|
||||
"train":[
|
||||
"packard-poster-session-2019-03-20_2",
|
||||
"clark-center-intersection-2019-02-28_0",
|
||||
"huang-lane-2019-02-12_0",
|
||||
"memorial-court-2019-03-16_0",
|
||||
"cubberly-auditorium-2019-04-22_0",
|
||||
"tressider-2019-04-26_2",
|
||||
"jordan-hall-2019-04-22_0",
|
||||
"clark-center-2019-02-28_1",
|
||||
"gates-basement-elevators-2019-01-17_1",
|
||||
"stlc-111-2019-04-19_0",
|
||||
"forbes-cafe-2019-01-22_0",
|
||||
"tressider-2019-03-16_0",
|
||||
"svl-meeting-gates-2-2019-04-08_0",
|
||||
"huang-basement-2019-01-25_0",
|
||||
"nvidia-aud-2019-04-18_0",
|
||||
"hewlett-packard-intersection-2019-01-24_0",
|
||||
"bytes-cafe-2019-02-07_0",
|
||||
],
|
||||
"test":[
|
||||
"packard-poster-session-2019-03-20_1",
|
||||
"gates-to-clark-2019-02-28_1",
|
||||
"packard-poster-session-2019-03-20_0",
|
||||
"tressider-2019-03-16_1",
|
||||
"clark-center-2019-02-28_0",
|
||||
"svl-meeting-gates-2-2019-04-08_1",
|
||||
"meyer-green-2019-03-16_0",
|
||||
"gates-159-group-meeting-2019-04-03_0",
|
||||
"huang-2-2019-01-25_0",
|
||||
"gates-ai-lab-2019-02-08_0",
|
||||
]
|
||||
}
|
||||
|
||||
|
||||
def get_dataloader(split, batch_size, num_workers, shuffle, dataset_pth, scan_type):
|
||||
ds_cfg = dataset_pth[0] if isinstance(dataset_pth, list) else dataset_pth
|
||||
print(ds_cfg, dataset_pth)
|
||||
if "DROW" in ds_cfg:
|
||||
from .drow_dataset import DROWDataset
|
||||
|
||||
ds = DROWDataset(split, dataset_pth, scan_type)
|
||||
elif "JRDB" in ds_cfg:
|
||||
from .jrdb_dataset import JRDBDataset
|
||||
ds = JRDBDataset(split, _JRDB_SPLIT, dataset_pth, scan_type) # no tracking support as for now
|
||||
else:
|
||||
raise RuntimeError(f"Unknown dataset {dataset_pth}.")
|
||||
|
||||
return DataLoader(
|
||||
ds,
|
||||
batch_size=batch_size,
|
||||
pin_memory=True,
|
||||
num_workers=num_workers,
|
||||
shuffle=shuffle,
|
||||
collate_fn=ds.collect_batch,
|
||||
)
|
||||
|
@@ -0,0 +1,158 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import numpy as np
|
||||
from torch.utils.data import Dataset
|
||||
|
||||
from srcs.data_handle.drow_handle import DROWv2Handle
|
||||
import srcs.utils.utils as u
|
||||
|
||||
|
||||
class DROWDataset(Dataset):
|
||||
def __init__(self, split, data_dir, scan_type):
|
||||
self._data_handle = {"data_dir": data_dir,
|
||||
"num_scans": 1 if scan_type == "DROW3" else 10,
|
||||
"scan_stride": 1}
|
||||
self._cutout_kwargs = {
|
||||
"win_width": 1.0,
|
||||
"win_depth": 0.5,
|
||||
"num_ct_pts": 56,
|
||||
"pad_val": 29.99,
|
||||
}
|
||||
self.__handle = DROWv2Handle(split, self._data_handle)
|
||||
self.__split = split
|
||||
|
||||
self._augment_data = False
|
||||
self._pedestrain_only = True
|
||||
self._cutout_kwargs = self._cutout_kwargs
|
||||
|
||||
def __getitem__(self, idx):
|
||||
drow_set = self.__handle[idx]
|
||||
|
||||
# regression target
|
||||
tar_cls, tar_reg = _get_target_cls_et_reg(
|
||||
drow_set["scans"][-1],
|
||||
drow_set["scan_phi"],
|
||||
drow_set["dets_wc"],
|
||||
drow_set["dets_wa"],
|
||||
drow_set["dets_wp"],
|
||||
0.6,
|
||||
0.4,
|
||||
0.35,
|
||||
1,
|
||||
2,
|
||||
3,
|
||||
self._pedestrain_only,
|
||||
)
|
||||
|
||||
drow_set["target_cls"] = tar_cls
|
||||
drow_set["target_reg"] = tar_reg
|
||||
|
||||
|
||||
drow_set["input"] = u.trim_the_scans(
|
||||
drow_set["scans"], drow_set["scan_phi"], stride=1, **self._cutout_kwargs
|
||||
)
|
||||
|
||||
# to be consistent with JRDB dataset
|
||||
drow_set["frame_id"] = drow_set["idx"]
|
||||
drow_set["sequence"] = "all"
|
||||
|
||||
# this is used by JRDB dataset to mask out annotations, to be consistent
|
||||
drow_set["anns_valid_mask"] = np.ones(len(drow_set["dets_wp"]), dtype=np.bool)
|
||||
|
||||
return drow_set
|
||||
|
||||
def __len__(self):
|
||||
return len(self.__handle)
|
||||
|
||||
@property
|
||||
def split(self):
|
||||
return self.__split # used by trainer.py
|
||||
|
||||
def collect_batch(self, batch):
|
||||
drow_rtn = {}
|
||||
for k, _ in batch[0].items():
|
||||
if k in ["target_cls", "target_reg", "input"]:
|
||||
drow_rtn[k] = np.array([sample[k] for sample in batch])
|
||||
else:
|
||||
drow_rtn[k] = [sample[k] for sample in batch]
|
||||
|
||||
return drow_rtn
|
||||
|
||||
|
||||
def _get_target_cls_et_reg(
|
||||
scan,
|
||||
scan_phi,
|
||||
wcs,
|
||||
was,
|
||||
wps,
|
||||
radii_wc,
|
||||
radii_wa,
|
||||
radii_wp,
|
||||
gts_wc,
|
||||
gts_wa,
|
||||
gts_wp,
|
||||
pedestrain_only,
|
||||
):
|
||||
tol_points = len(scan)
|
||||
tar_cls = np.zeros(tol_points, dtype=np.int64)
|
||||
tar_reg = np.zeros((tol_points, 2), dtype=np.float32)
|
||||
|
||||
if pedestrain_only:
|
||||
all_dets = list(wps)
|
||||
all_radius = [radii_wp] * len(wps)
|
||||
labels = [0] + [1] * len(wps)
|
||||
else:
|
||||
all_dets = list(wcs) + list(was) + list(wps)
|
||||
all_radius = (
|
||||
[radii_wc] * len(wcs) + [radii_wa] * len(was) + [radii_wp] * len(wps)
|
||||
)
|
||||
labels = (
|
||||
[0] + [gts_wc] * len(wcs) + [gts_wa] * len(was) + [gts_wp] * len(wps)
|
||||
)
|
||||
|
||||
dets_refined = _nearest_result(scan, scan_phi, all_dets, all_radius)
|
||||
# reshape list
|
||||
dets_refined = np.asarray(dets_refined).squeeze()
|
||||
|
||||
for i, (r, phi) in enumerate(zip(scan, scan_phi)):
|
||||
if 0 < dets_refined[i]:
|
||||
tar_cls[i] = labels[dets_refined[i]]
|
||||
tar_reg[i, :] = u.global_to_canonical(r, phi, *all_dets[dets_refined[i] - 1])
|
||||
|
||||
return tar_cls, tar_reg
|
||||
|
||||
|
||||
def _nearest_result(scan, scan_phi, dets, radii):
|
||||
|
||||
if len(dets) == 0:
|
||||
return np.zeros_like(scan, dtype=int)
|
||||
|
||||
assert len(dets) == len(radii), "Need to give a radius for each detection!"
|
||||
|
||||
# Distance (in x,y space) of each laser-point with each detection.
|
||||
scans_xy = np.array(u.rphi_to_xy(scan, scan_phi)).T # (N, 2)
|
||||
dets_xy = np.array([u.rphi_to_xy(r, phi) for r, phi in dets]) # (N,2) same here
|
||||
mat_mul = np.dot(scans_xy, dets_xy.T)
|
||||
te = np.square(scans_xy).sum(axis=1)
|
||||
tr = np.square(dets_xy).sum(axis=1)
|
||||
dists = np.sqrt(-2*mat_mul + np.matrix(tr) + np.matrix(te).T)
|
||||
|
||||
# Subtract the radius from the distances, such that they are < 0 if inside,
|
||||
# > 0 if outside.
|
||||
dists -= radii
|
||||
|
||||
# Prepend zeros so that argmin is 0 for everything "outside".
|
||||
dists = np.hstack([np.zeros((len(scan), 1)), dists])
|
||||
|
||||
return np.argmin(dists, axis=1)
|
||||
|
@@ -0,0 +1,228 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from collections import defaultdict
|
||||
import numpy as np
|
||||
from torch.utils.data import Dataset
|
||||
|
||||
from srcs.data_handle.jrdb_handle import JRDBv1Handle
|
||||
import srcs.utils.utils as u
|
||||
|
||||
|
||||
__all__ = ["JRDBDataset"]
|
||||
|
||||
|
||||
# laser to base
|
||||
_ROT_Z = np.pi / 120
|
||||
_R_laser_to_base = np.array([[np.cos(_ROT_Z), -np.sin(_ROT_Z), 0],
|
||||
[np.sin(_ROT_Z), np.cos(_ROT_Z), 0],
|
||||
[0, 0, 1]],
|
||||
dtype=np.float32)
|
||||
|
||||
|
||||
class JRDBDataset(Dataset):
|
||||
def __init__(self, split, jrdb_split, data_dir_cfg, scan_type):
|
||||
self._data_handle = { "data_dir": data_dir_cfg[0] if isinstance(data_dir_cfg, list) else data_dir_cfg,
|
||||
"num_scans": 1 if scan_type == "DROW3" else 10,
|
||||
"scan_stride": 1,
|
||||
"tracking": False
|
||||
}
|
||||
|
||||
self._jrdb_split = jrdb_split
|
||||
|
||||
if split == "train":
|
||||
self.__handle = JRDBv1Handle(
|
||||
"train", self._data_handle, sequences=defaultdict(lambda: self._jrdb_split.get("train", "abc"))[0]
|
||||
)
|
||||
elif split == "val" or split == "test":
|
||||
self.__handle = JRDBv1Handle(
|
||||
"train", self._data_handle, sequences=defaultdict(lambda: self._jrdb_split.get("test", "abc"))[0]
|
||||
)
|
||||
elif split == "train_val":
|
||||
self.__handle = JRDBv1Handle("train", self._data_handle)
|
||||
elif split == "test_nano" or split == "train_nano":
|
||||
self.__handle = JRDBv1Handle(split.split("_")[0], self._data_handle, sequences=[data_dir_cfg[1]])
|
||||
elif split == "test_single" or split == "train_single":
|
||||
self.__handle = JRDBv1Handle(split.split("_")[0], self._data_handle, sequences=[self._jrdb_split])
|
||||
else:
|
||||
raise RuntimeError(f"Invalid split: {split}")
|
||||
|
||||
self.__split = split
|
||||
|
||||
self._augment_data = False
|
||||
self._person_only = True
|
||||
self._cutout_kwargs = {
|
||||
"win_width": 1.0,
|
||||
"win_depth": 0.5,
|
||||
"num_ct_pts": 56,
|
||||
"pad_val": 29.99,
|
||||
}
|
||||
self._pseudo_label = False
|
||||
self._pl_correction_level = 0
|
||||
|
||||
def __len__(self):
|
||||
return len(self.__handle)
|
||||
|
||||
def __getitem__(self, idx):
|
||||
return self._next_jrdb_sample(idx)
|
||||
|
||||
@property
|
||||
def split(self):
|
||||
return self.__split
|
||||
|
||||
@property
|
||||
def sequence_beginning_inds(self):
|
||||
return self.__handle.sequence_beginning_inds
|
||||
|
||||
def collect_batch(self, batch):
|
||||
jrdb_rtn = {}
|
||||
for k, _ in batch[0].items():
|
||||
if k in [
|
||||
"target_cls",
|
||||
"target_reg",
|
||||
"input",
|
||||
]:
|
||||
jrdb_rtn[k] = np.array([sample[k] for sample in batch])
|
||||
else:
|
||||
jrdb_rtn[k] = [sample[k] for sample in batch]
|
||||
|
||||
return jrdb_rtn
|
||||
|
||||
def _next_jrdb_sample(self, idx):
|
||||
jrdb_set = self.__handle[idx]
|
||||
|
||||
# DROW defines laser frame as x-forward, y-right, z-downward
|
||||
# JRDB defines laser frame as x-forward, y-left, z-upward
|
||||
# Use DROW frame for DR-SPAAM or DROW3
|
||||
|
||||
# equivalent of flipping y axis (inversing laser phi angle)
|
||||
jrdb_set["laser_data"] = jrdb_set["laser_data"][:, ::-1]
|
||||
scan_rphi = np.stack(
|
||||
(jrdb_set["laser_data"][-1], jrdb_set["laser_grid"]), axis=0
|
||||
)
|
||||
|
||||
# get annotation in laser frame
|
||||
pc_xyz = [
|
||||
(pc["box"]["cx"], pc["box"]["cy"], pc["box"]["cz"])
|
||||
for pc in jrdb_set["pc_anns"]
|
||||
]
|
||||
if len(pc_xyz) > 0:
|
||||
pc_xyz = np.array(pc_xyz, dtype=np.float32).T
|
||||
pc_xyz = _R_laser_to_base.T @ pc_xyz
|
||||
pc_xyz[1] = -pc_xyz[1] # to DROW frame
|
||||
dets_rphi = np.stack(u.xy_to_rphi(pc_xyz[0], pc_xyz[1]), axis=0)
|
||||
else:
|
||||
dets_rphi = []
|
||||
|
||||
# regression target
|
||||
tar_cls, tar_reg, anns_valid_mask = _get_target_cls_et_reg(
|
||||
scan_rphi,
|
||||
dets_rphi,
|
||||
person_rad_petit=0.4,
|
||||
person_rad_grand=0.8,
|
||||
)
|
||||
|
||||
jrdb_set["target_cls"] = tar_cls
|
||||
jrdb_set["target_reg"] = tar_reg
|
||||
jrdb_set["anns_valid_mask"] = anns_valid_mask
|
||||
|
||||
|
||||
# to be consistent with DROWDataset in order to use the same evaluation function
|
||||
dets_wp = []
|
||||
for i in range(dets_rphi.shape[1]):
|
||||
dets_wp.append((dets_rphi[0, i], dets_rphi[1, i]))
|
||||
jrdb_set["dets_wp"] = dets_wp
|
||||
jrdb_set["scans"] = jrdb_set["laser_data"]
|
||||
jrdb_set["scan_phi"] = jrdb_set["laser_grid"]
|
||||
|
||||
|
||||
jrdb_set["input"] = u.trim_the_scans(
|
||||
jrdb_set["laser_data"],
|
||||
jrdb_set["laser_grid"],
|
||||
stride=1,
|
||||
**self._cutout_kwargs,
|
||||
)
|
||||
|
||||
return jrdb_set
|
||||
|
||||
|
||||
|
||||
def transform_pts_base_to_stitched_im(pts):
|
||||
|
||||
im_size = (480, 3760)
|
||||
|
||||
# to image coordinate
|
||||
pts_rect = pts[[1, 2, 0], :]
|
||||
pts_rect[:2, :] *= -1
|
||||
|
||||
# to pixel
|
||||
horizontal_theta = np.arctan2(pts_rect[0], pts_rect[2])
|
||||
horizontal_percent = horizontal_theta / (2 * np.pi) + 0.5
|
||||
x = im_size[1] * horizontal_percent
|
||||
y = (
|
||||
485.78 * pts_rect[1] / pts_rect[2] * np.cos(horizontal_theta)
|
||||
+ 0.4375 * im_size[0]
|
||||
)
|
||||
|
||||
inbound_mask = y < im_size[0]
|
||||
|
||||
return np.stack((x, y), axis=0).astype(np.int32), inbound_mask
|
||||
|
||||
|
||||
def _get_target_cls_et_reg(
|
||||
scan_rphi, dets_rphi, person_rad_petit, person_rad_grand
|
||||
):
|
||||
_, num_scans = scan_rphi.shape
|
||||
|
||||
# no annotation in this frame
|
||||
if len(dets_rphi) == 0:
|
||||
tar_cls = np.zeros(num_scans, dtype=np.int64)
|
||||
tar_reg = np.zeros((num_scans, 2), dtype=np.float32)
|
||||
anns_mask = []
|
||||
|
||||
else:
|
||||
min_adj_pts = 5
|
||||
scan_r, scan_phi = scan_rphi[0], scan_rphi[1]
|
||||
det_r, det_phi = dets_rphi[0], dets_rphi[1]
|
||||
scan_x = np.expand_dims(scan_r * np.cos(scan_phi), axis=0)
|
||||
scan_y = np.expand_dims(scan_r * np.sin(scan_phi), axis=0)
|
||||
dets_x = np.expand_dims(det_r * np.cos(det_phi), axis=1)
|
||||
dets_y = np.expand_dims(det_r * np.sin(det_phi), axis=1)
|
||||
|
||||
pairwise_dist = np.hypot(scan_x - dets_x, scan_y - dets_y)
|
||||
|
||||
# mark out annotations that has too few scan points
|
||||
anns_mask = (
|
||||
np.sum(pairwise_dist < person_rad_petit, axis=1) > min_adj_pts
|
||||
) # (M, )
|
||||
|
||||
# for each point, find the distance to its closest annotation
|
||||
argmin_pairwise_dist = np.argmin(pairwise_dist, axis=0) # (n_scan, )
|
||||
min_pairwise_dist = pairwise_dist[argmin_pairwise_dist, np.arange(num_scans)]
|
||||
|
||||
# points within small radius, whose corresponding annotation is valid, is marked
|
||||
# as foreground
|
||||
tar_cls = -1 * np.ones(num_scans, dtype=np.int64)
|
||||
valid_mask = np.logical_and(
|
||||
anns_mask[argmin_pairwise_dist], min_pairwise_dist < person_rad_petit
|
||||
)
|
||||
tar_cls[valid_mask] = 1
|
||||
tar_cls[min_pairwise_dist > person_rad_grand] = 0
|
||||
|
||||
# regression target
|
||||
dets_matched_r = dets_rphi[:, argmin_pairwise_dist][0]
|
||||
dets_matched_phi = dets_rphi[:, argmin_pairwise_dist][1]
|
||||
tar_reg_x = np.sin(dets_matched_phi - scan_phi) * dets_matched_r
|
||||
tar_reg_y = np.cos(dets_matched_phi - scan_phi) * dets_matched_r - scan_r
|
||||
tar_reg = np.stack([tar_reg_x, tar_reg_y], axis=1)
|
||||
|
||||
return tar_cls, tar_reg, anns_mask
|
172
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/detector.py
Normal file
172
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/detector.py
Normal file
@@ -0,0 +1,172 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import math
|
||||
import torch
|
||||
import numpy as np
|
||||
|
||||
from srcs.nets.drow_net import DrowNet
|
||||
from srcs.nets.dr_spaam import DrSpaam
|
||||
|
||||
_PI = np.pi
|
||||
|
||||
__all__ = ["Detector", "scans_to_cutout"]
|
||||
|
||||
|
||||
class Detector(object):
|
||||
def __init__(
|
||||
self, ckpt_file, dataset="JRDB", model="DROW3", gpu=True, stride=1, panoramic_scan=False
|
||||
):
|
||||
"""A warpper class around DROW3 or DR-SPAAM network for end-to-end inference.
|
||||
|
||||
Args:
|
||||
ckpt_file (str): Path to checkpoint
|
||||
model (str): Model name, "DROW3" or "DR-SPAAM".
|
||||
gpu (bool): True to use GPU. Defaults to True.
|
||||
stride (int): Downsample scans for faster inference.
|
||||
panoramic_scan (bool): True if the scan covers 360 degree.
|
||||
"""
|
||||
self._device = gpu
|
||||
self._stride = stride
|
||||
self._use_dr_spaam = model == "DR-SPAAM"
|
||||
|
||||
self._scan_phi = None
|
||||
self.data = np.random.rand(56)
|
||||
|
||||
if "jrdb" in dataset or "JRDB" in dataset:
|
||||
self._laser_fov_deg = 360
|
||||
elif "drow" in dataset or "DROW" in dataset:
|
||||
self._laser_fov_deg = 225
|
||||
else:
|
||||
raise NotImplementedError(
|
||||
"Received unsupported dataset {}, break.".format(
|
||||
dataset
|
||||
)
|
||||
)
|
||||
if model == "DROW3":
|
||||
self._model = DrowNet(
|
||||
dropout=0.5, cls_loss=None)
|
||||
elif model == "DR-SPAAM":
|
||||
self._model = DrSpaam(
|
||||
dropout=0.5,
|
||||
num_pts=56,
|
||||
embedding_length=128,
|
||||
alpha=0.5,
|
||||
window_size=17,
|
||||
panoramic_scan=panoramic_scan,
|
||||
cls_loss=None,
|
||||
)
|
||||
else:
|
||||
raise NotImplementedError(
|
||||
"Received unsupported model {}, break.".format(
|
||||
model
|
||||
)
|
||||
)
|
||||
|
||||
ckpt = torch.load(ckpt_file)
|
||||
self._model.load_state_dict(ckpt["model_state"])
|
||||
self.model = self._model
|
||||
self._model.eval()
|
||||
if gpu:
|
||||
torch.backends.cudnn.benchmark = True
|
||||
self._model = self._model.cuda()
|
||||
|
||||
|
||||
def return_data(self, scan):
|
||||
bisec_fov_rad = 0.5 * np.deg2rad(self._laser_fov_deg)
|
||||
self._scan_phi = np.linspace(
|
||||
-bisec_fov_rad, bisec_fov_rad, max(scan.shape), dtype=np.float32
|
||||
)
|
||||
|
||||
# preprocess
|
||||
ct = scans_to_cutout(
|
||||
scan,
|
||||
self._scan_phi,
|
||||
stride=self._stride,
|
||||
win_size=[1.0, 0.5],
|
||||
num_cutout_pts=56,
|
||||
padding_val=29.99,
|
||||
)
|
||||
ct = torch.from_numpy(ct).float()
|
||||
|
||||
if self._device:
|
||||
ct = ct.cuda()
|
||||
return ct.unsqueeze(dim=0)
|
||||
|
||||
|
||||
def scans_to_cutout(
|
||||
scans,
|
||||
scan_phi,
|
||||
stride=1,
|
||||
win_size=None,
|
||||
num_cutout_pts=56,
|
||||
padding_val=29.99,
|
||||
):
|
||||
|
||||
num_scans, num_pts = scans.shape # (1, num_pts)
|
||||
|
||||
# size (width) of the window
|
||||
pt_dists = scans[:, ::stride]
|
||||
bisec_alp = np.arctan(0.5 * win_size[0] / np.maximum(pt_dists, 1e-2))
|
||||
scan_diff = scan_phi[1] - scan_phi[0]
|
||||
# cutout indices
|
||||
del_alp = 2.0 * bisec_alp / (num_cutout_pts - 1)
|
||||
ang_cutout = (
|
||||
scan_phi[::stride]
|
||||
- bisec_alp
|
||||
+ np.arange(num_cutout_pts).reshape(num_cutout_pts, 1, 1) * del_alp
|
||||
)
|
||||
ang_cutout = (ang_cutout + _PI) % (2.0 * _PI) - _PI # warp angle
|
||||
inds_cutout = (ang_cutout - scan_phi[0]) / scan_diff
|
||||
outter_mask = np.logical_or(inds_cutout < 0, inds_cutout > num_pts - 1)
|
||||
|
||||
# cutout (linear interp)
|
||||
inds_cutout_lower = np.core.umath.clip(np.floor(inds_cutout), 0, num_pts - 1).astype(np.int32)
|
||||
inds_cutout_upper = np.core.umath.clip(inds_cutout_lower + 1, 0, num_pts - 1).astype(np.int32)
|
||||
inds_ct_ratio = np.core.umath.clip(inds_cutout - inds_cutout_lower, 0.0, 1.0)
|
||||
|
||||
inds_offset = (np.arange(num_scans).reshape(1, num_scans, 1) * num_pts)
|
||||
cutout_lower = np.take(scans, inds_cutout_lower + inds_offset)
|
||||
cutout_upper = np.take(scans, inds_cutout_upper + inds_offset)
|
||||
ct0 = cutout_lower + inds_ct_ratio * (cutout_upper - cutout_lower)
|
||||
|
||||
# use area sampling for down-sampling (close points)
|
||||
if True:
|
||||
num_pts_win = inds_cutout[-1] - inds_cutout[0]
|
||||
area_mask = num_pts_win > num_cutout_pts
|
||||
if np.sum(area_mask) > 0:
|
||||
# sample the window with more points than the actual number of points
|
||||
sample_area = int(math.ceil(np.max(num_pts_win) / num_cutout_pts))
|
||||
num_ct_pts_area = sample_area * num_cutout_pts
|
||||
del_alp_area = 2.0 * bisec_alp / (num_ct_pts_area - 1)
|
||||
ang_ct_area = (
|
||||
scan_phi[::stride]
|
||||
- bisec_alp
|
||||
+ np.arange(num_ct_pts_area).reshape(num_ct_pts_area, 1, 1)
|
||||
* del_alp_area
|
||||
)
|
||||
ang_ct_area = (ang_ct_area + _PI) % (2.0 * _PI) - _PI # warp angle
|
||||
inds_ct_area = (ang_ct_area - scan_phi[0]) / scan_diff
|
||||
inds_ct_area = np.rint(np.core.umath.clip(inds_ct_area, 0, num_pts - 1)).astype(np.int32)
|
||||
ct_area = np.take(scans, inds_ct_area + inds_offset)
|
||||
ct_area = ct_area.reshape(
|
||||
num_cutout_pts, sample_area, num_scans, pt_dists.shape[1]
|
||||
).mean(axis=1)
|
||||
ct0[:, area_mask] = ct_area[:, area_mask]
|
||||
|
||||
# normalize cutout
|
||||
ct0[outter_mask] = padding_val
|
||||
ct1 = np.core.umath.clip(ct0, pt_dists - win_size[1], pt_dists + win_size[1])
|
||||
ct1 = (ct1 - pt_dists) / win_size[1]
|
||||
cutout_scan = np.ascontiguousarray(ct1.transpose((2, 1, 0)), dtype=np.float32)
|
||||
|
||||
return cutout_scan
|
14
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/__init__.py
Normal file
14
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/__init__.py
Normal file
@@ -0,0 +1,14 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from .dr_spaam import DrSpaam
|
||||
from .drow_net import DrowNet
|
205
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/dr_spaam.py
Normal file
205
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/dr_spaam.py
Normal file
@@ -0,0 +1,205 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from math import ceil
|
||||
import torch
|
||||
import torch.nn as nn
|
||||
import torch.nn.functional as F
|
||||
|
||||
|
||||
class DrSpaam(nn.Module):
|
||||
def __init__(
|
||||
self,
|
||||
dropout=0.5,
|
||||
num_pts=48,
|
||||
alpha=0.5,
|
||||
embed_len=128,
|
||||
win_size=7,
|
||||
pano_scan=False,
|
||||
cls_loss=None,
|
||||
):
|
||||
super(DrSpaam, self).__init__()
|
||||
|
||||
self.dropout = dropout
|
||||
|
||||
# backbone
|
||||
self.conv_u1 = nn.Sequential(
|
||||
self._conv_1d(1, 64), self._conv_1d(64, 64), self._conv_1d(64, 128)
|
||||
)
|
||||
self.conv_u2 = nn.Sequential(
|
||||
self._conv_1d(128, 128), self._conv_1d(128, 128), self._conv_1d(128, 256)
|
||||
)
|
||||
self.conv_u3 = nn.Sequential(
|
||||
self._conv_1d(256, 256), self._conv_1d(256, 256), self._conv_1d(256, 512)
|
||||
)
|
||||
self.conv_u4 = nn.Sequential(self._conv_1d(512, 256), self._conv_1d(256, 128))
|
||||
|
||||
# detection layer
|
||||
self.head_cls = nn.Conv1d(128, 1, kernel_size=1)
|
||||
self.head_reg = nn.Conv1d(128, 2, kernel_size=1)
|
||||
|
||||
# spatial attention
|
||||
self.spatial_attention_memory = _SpatialAttentionMemory(
|
||||
n_pts=int(ceil(num_pts / 4)),
|
||||
n_channel=256,
|
||||
embed_len=embed_len,
|
||||
alpha=alpha,
|
||||
win_size=win_size,
|
||||
pano_scan=pano_scan,
|
||||
)
|
||||
|
||||
# initialize weights
|
||||
for idx, module in enumerate(self.modules()):
|
||||
if isinstance(module, (nn.Conv1d, nn.Conv2d)):
|
||||
nn.init.kaiming_normal_(module.weight, a=0.1, nonlinearity="leaky_relu")
|
||||
elif isinstance(module, (nn.BatchNorm1d, nn.BatchNorm2d)):
|
||||
nn.init.constant_(module.weight, 1)
|
||||
nn.init.constant_(module.bias, 0)
|
||||
|
||||
def forward(self, signal, inference=False):
|
||||
|
||||
n_bs, n_cutout, n_scan, n_pc = signal.shape
|
||||
|
||||
if not inference:
|
||||
self.spatial_attention_memory.reset()
|
||||
|
||||
# process scan sequentially
|
||||
n_scan = signal.shape[2]
|
||||
for i in range(n_scan):
|
||||
signal_i = signal[:, :, i, :] # (bs, cutout, pc)
|
||||
|
||||
# extract feature from current scan
|
||||
flow = signal_i.view(n_bs * n_cutout, 1, n_pc)
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_u1) # /2
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_u2) # /4
|
||||
flow = flow.view(n_bs, n_cutout, flow.shape[-2], flow.shape[-1]) # (bs, cutout, C, pc)
|
||||
|
||||
# combine current feature with memory
|
||||
flow, sim_score = self.spatial_attention_memory(flow) # (bs, cutout, C, pc)
|
||||
|
||||
# detection using combined feature memory
|
||||
flow = flow.view(n_bs * n_cutout, flow.shape[-2], flow.shape[-1])
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_u3) # /8
|
||||
flow = self.conv_u4(flow)
|
||||
flow = F.avg_pool1d(flow, kernel_size=flow.shape[-1]) # (bs * cutout, C, 1)
|
||||
|
||||
pred_cls = self.head_cls(flow).view(n_bs, n_cutout, -1) # (bs, cutout, cls)
|
||||
pred_reg = self.head_reg(flow).view(n_bs, n_cutout, 2) # (bs, cutout, 2)
|
||||
|
||||
return pred_cls, pred_reg, sim_score
|
||||
|
||||
def _conv_et_pool_1d(self, signal, conv_block):
|
||||
flow = conv_block(signal)
|
||||
flow = F.max_pool1d(flow, kernel_size=2)
|
||||
if self.dropout > 0:
|
||||
flow = F.dropout(flow, p=self.dropout, training=self.training)
|
||||
|
||||
return flow
|
||||
|
||||
def _conv_1d(self, in_channel, out_channel):
|
||||
return nn.Sequential(
|
||||
nn.Conv1d(in_channel, out_channel, kernel_size=3, padding=1),
|
||||
nn.BatchNorm1d(out_channel),
|
||||
nn.LeakyReLU(negative_slope=0.1, inplace=True),
|
||||
)
|
||||
|
||||
|
||||
class _SpatialAttentionMemory(nn.Module):
|
||||
def __init__(
|
||||
self, n_pts, n_channel, embed_len, alpha, win_size, pano_scan
|
||||
):
|
||||
|
||||
super(_SpatialAttentionMemory, self).__init__()
|
||||
self._alpha = alpha
|
||||
self._win_size = win_size
|
||||
self._embed_len = embed_len
|
||||
self._pano_scan = pano_scan
|
||||
|
||||
self.atten_mem = None
|
||||
self.neighbour_masks = None
|
||||
self.neighbour_inds = None
|
||||
|
||||
self.custom_conv = nn.Sequential(
|
||||
nn.Conv1d(n_channel, self._embed_len, kernel_size=n_pts, padding=0),
|
||||
nn.BatchNorm1d(self._embed_len),
|
||||
nn.LeakyReLU(negative_slope=0.1, inplace=True),
|
||||
)
|
||||
|
||||
for idx, module in enumerate(self.modules()):
|
||||
if isinstance(module, (nn.Conv1d, nn.Conv2d)):
|
||||
nn.init.kaiming_normal_(module.weight, a=0.1, nonlinearity="leaky_relu")
|
||||
elif isinstance(module, (nn.BatchNorm1d, nn.BatchNorm2d)):
|
||||
nn.init.constant_(module.weight, 1)
|
||||
nn.init.constant_(module.bias, 0)
|
||||
|
||||
def reset(self):
|
||||
self.atten_mem = None
|
||||
|
||||
def forward(self, sig_new):
|
||||
if self.atten_mem is None:
|
||||
self.atten_mem = sig_new
|
||||
return self.atten_mem, None
|
||||
|
||||
n_batch, n_cutout, n_channel, n_pts = sig_new.shape
|
||||
|
||||
|
||||
self.neighbour_masks, self.neighbour_inds = self._generate_neighbour_masks(
|
||||
sig_new
|
||||
)
|
||||
|
||||
embed_x = self.custom_conv(
|
||||
sig_new.view(-1, n_channel, n_pts)
|
||||
).view(-1, n_cutout, self._embed_len)
|
||||
|
||||
|
||||
embed_tmp = self.custom_conv(
|
||||
self.atten_mem.view(-1, n_channel, n_pts)
|
||||
).view(-1, n_cutout, self._embed_len)
|
||||
|
||||
# pair-wise similarity (batch, cutout, cutout)
|
||||
sim_score = torch.matmul(embed_x, embed_tmp.permute(0, 2, 1))
|
||||
|
||||
# masked softmax
|
||||
sim_score = sim_score - 1e10 * (1.0 - self.neighbour_masks)
|
||||
max_sim = sim_score.max(dim=-1, keepdim=True)[0]
|
||||
exp_sim = torch.exp(sim_score - max_sim) * self.neighbour_masks
|
||||
exps_sum = exp_sim.sum(dim=-1, keepdim=True)
|
||||
sim_score = exp_sim / exps_sum
|
||||
|
||||
# weighted average on the template
|
||||
atten_mem = self.atten_mem.view(n_batch, n_cutout, -1)
|
||||
atten_mem_w = torch.matmul(sim_score, atten_mem).view(-1, n_cutout, n_channel, n_pts)
|
||||
|
||||
# update memory using auto-regressive
|
||||
self.atten_mem = self._alpha * sig_new + (1.0 - self._alpha) * atten_mem_w
|
||||
|
||||
return self.atten_mem, sim_score
|
||||
|
||||
def _generate_neighbour_masks(self, sig):
|
||||
|
||||
n_cutout = sig.shape[1]
|
||||
half_ws = int(self._win_size / 2)
|
||||
inds_col = torch.arange(n_cutout).unsqueeze(dim=-1).long()
|
||||
win_inds = torch.arange(-half_ws, half_ws + 1).long()
|
||||
inds_col = inds_col + win_inds.unsqueeze(dim=0) # (cutout, neighbours)
|
||||
|
||||
inds_col = (
|
||||
inds_col % n_cutout
|
||||
if self._pano_scan and not self.training
|
||||
else inds_col.clamp(min=0, max=n_cutout - 1)
|
||||
)
|
||||
inds_row = torch.arange(n_cutout).unsqueeze(dim=-1).expand_as(inds_col).long()
|
||||
inds_full = torch.stack((inds_row, inds_col), dim=2).view(-1, 2)
|
||||
|
||||
nb_masks = torch.zeros(n_cutout, n_cutout).float()
|
||||
nb_masks[inds_full[:, 0], inds_full[:, 1]] = 1.0
|
||||
return nb_masks.cuda(sig.get_device()) if sig.is_cuda else nb_masks, inds_full
|
88
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/drow_net.py
Normal file
88
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/nets/drow_net.py
Normal file
@@ -0,0 +1,88 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import torch
|
||||
import torch.nn as nn
|
||||
import torch.nn.functional as Func
|
||||
|
||||
|
||||
class DrowNet(nn.Module):
|
||||
def __init__(self, dropout=0.5, cls_loss=None):
|
||||
super(DrowNet, self).__init__()
|
||||
|
||||
self.dropout = dropout
|
||||
|
||||
self.conv_block_1 = nn.Sequential(
|
||||
self._conv_1d(1, 64), self._conv_1d(64, 64), self._conv_1d(64, 128)
|
||||
)
|
||||
self.conv_block_2 = nn.Sequential(
|
||||
self._conv_1d(128, 128), self._conv_1d(128, 128), self._conv_1d(128, 256)
|
||||
)
|
||||
self.conv_block_3 = nn.Sequential(
|
||||
self._conv_1d(256, 256), self._conv_1d(256, 256), self._conv_1d(256, 512)
|
||||
)
|
||||
self.conv_block_4 = nn.Sequential(self._conv_1d(512, 256), self._conv_1d(256, 128))
|
||||
|
||||
self.conv_cls = nn.Conv1d(128, 1, kernel_size=1)
|
||||
self.conv_reg = nn.Conv1d(128, 2, kernel_size=1)
|
||||
|
||||
# classification loss
|
||||
self.cls_loss = (
|
||||
cls_loss if cls_loss is not None else Func.binary_cross_entropy_with_logits
|
||||
)
|
||||
|
||||
# initialize weights
|
||||
for m in self.modules():
|
||||
if isinstance(m, (nn.Conv1d, nn.Conv2d)):
|
||||
nn.init.kaiming_normal_(m.weight, a=0.1, nonlinearity="leaky_relu")
|
||||
elif isinstance(m, (nn.BatchNorm1d, nn.BatchNorm2d)):
|
||||
nn.init.constant_(m.weight, 1)
|
||||
nn.init.constant_(m.bias, 0)
|
||||
|
||||
def forward(self, signal):
|
||||
|
||||
num_bs, num_ct, num_sc, num_pt = signal.shape
|
||||
|
||||
# start with scans
|
||||
flow = signal.view(-1, 1, num_pt)
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_block_1)
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_block_2)
|
||||
|
||||
flow = flow.view(num_bs, num_ct, num_sc, flow.shape[-2], flow.shape[-1])
|
||||
flow = torch.sum(flow, dim=2)
|
||||
|
||||
# forward fused cutout
|
||||
flow = flow.view(num_bs * num_ct, flow.shape[-2], flow.shape[-1])
|
||||
flow = self._conv_et_pool_1d(flow, self.conv_block_3)
|
||||
flow = self.conv_block_4(flow)
|
||||
|
||||
flow = Func.avg_pool1d(flow, kernel_size=7)
|
||||
|
||||
pred_cls = self.conv_cls(flow).view(num_bs, num_ct, -1)
|
||||
pred_reg = self.conv_reg(flow).view(num_bs, num_ct, 2)
|
||||
|
||||
return pred_cls, pred_reg
|
||||
|
||||
def _conv_et_pool_1d(self, signal, convblock):
|
||||
flow = convblock(signal)
|
||||
flow = Func.max_pool1d(flow, kernel_size=2)
|
||||
if self.dropout > 0:
|
||||
flow = Func.dropout(flow, p=self.dropout, training=self.training)
|
||||
|
||||
return flow
|
||||
|
||||
def _conv_1d(self, in_channel, out_channel):
|
||||
return nn.Sequential(
|
||||
nn.Conv1d(in_channel, out_channel, kernel_size=3, padding=1),
|
||||
nn.BatchNorm1d(out_channel),
|
||||
nn.LeakyReLU(negative_slope=0.1, inplace=True),
|
||||
)
|
@@ -0,0 +1,12 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
@@ -0,0 +1,331 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
from collections import defaultdict
|
||||
import glob
|
||||
import os
|
||||
from typing import List, Tuple
|
||||
import itertools
|
||||
import numpy as np
|
||||
|
||||
|
||||
def eval_internal(
|
||||
dets_xy, dets_cls, dets_inds, gts_xy, gts_inds, ar
|
||||
):
|
||||
a_rad = ar * np.ones(len(gts_inds), dtype=np.float32)
|
||||
|
||||
finds = np.unique(np.r_[dets_inds, gts_inds])
|
||||
|
||||
det_accepted_idxs = defaultdict(list)
|
||||
tps = np.zeros(len(finds), dtype=np.uint32)
|
||||
fps = np.zeros(len(finds), dtype=np.uint32)
|
||||
fns = np.array([np.sum(gts_inds == f) for f in finds], dtype=np.uint32)
|
||||
|
||||
precisions = np.full_like(dets_cls, np.nan)
|
||||
recalls = np.full_like(dets_cls, np.nan)
|
||||
threshs = np.full_like(dets_cls, np.nan)
|
||||
|
||||
indices = np.argsort(dets_cls, kind="mergesort") # mergesort for determinism.
|
||||
for i, idx in enumerate(reversed(indices)):
|
||||
frame = dets_inds[idx]
|
||||
iframe = np.where(finds == frame)[0][0] # Can only be a single one.
|
||||
|
||||
# Accept this detection
|
||||
dets_idxs = det_accepted_idxs[frame]
|
||||
dets_idxs.append(idx)
|
||||
threshs[i] = dets_cls[idx]
|
||||
|
||||
dets = dets_xy[dets_idxs]
|
||||
|
||||
gts_mask = gts_inds == frame
|
||||
gts = gts_xy[gts_mask]
|
||||
radii = a_rad[gts_mask]
|
||||
|
||||
if len(gts) == 0: # No GT, but there is a detection.
|
||||
fps[iframe] += 1
|
||||
else:
|
||||
mat_mul = np.dot(gts, dets.T)
|
||||
te = np.square(gts).sum(axis=1)
|
||||
tr = np.square(dets).sum(axis=1)
|
||||
c_dists = np.sqrt(np.abs(-2*mat_mul + np.matrix(tr) + np.matrix(te).T))
|
||||
not_in_radius = radii[:, None] < c_dists # -> ngts x ndets, True (=1) if too far, False
|
||||
|
||||
igt, idet = linear_sum_assignment_hungarian(not_in_radius)
|
||||
|
||||
tps[iframe] = np.sum(np.logical_not(not_in_radius[igt, idet]))
|
||||
fps[iframe] = (len(dets) - tps[iframe])
|
||||
fns[iframe] = len(gts) - tps[iframe]
|
||||
|
||||
tp, fp, fn = np.sum(tps), np.sum(fps), np.sum(fns)
|
||||
precisions[i] = tp / (fp + tp) if fp + tp > 0 else np.nan
|
||||
recalls[i] = tp / (fn + tp) if fn + tp > 0 else np.nan
|
||||
# remove rounding errors
|
||||
invalid_recs = np.where(np.diff(recalls))[0]
|
||||
for idx in invalid_recs:
|
||||
tmp_idx = idx+2
|
||||
while recalls[tmp_idx] < recalls[idx]:
|
||||
tmp_idx += 1
|
||||
|
||||
# smooth out -- dirty fix
|
||||
recalls[idx: tmp_idx+1] = np.linspace(recalls[idx], recalls[tmp_idx], tmp_idx-idx+1)
|
||||
ap, peak_f1, eer = _get_ap_prec_rec(recalls, precisions)
|
||||
return {
|
||||
"precisions": precisions,
|
||||
"recalls": recalls,
|
||||
"thresholds": threshs,
|
||||
"ap": ap,
|
||||
"peak_f1": peak_f1,
|
||||
"eer": eer,
|
||||
}
|
||||
|
||||
|
||||
|
||||
def linear_sum_assignment_brute_force(
|
||||
cost_matrix: np.ndarray,
|
||||
maximize: bool = False) -> Tuple[List[int], List[int]]:
|
||||
""" maximize:True-> maximum weight matching; False->minimum cost"""
|
||||
cost_matrix = np.multiply(np.array(cost_matrix), 1)
|
||||
h = cost_matrix.shape[0]
|
||||
w = cost_matrix.shape[1]
|
||||
|
||||
if maximize is True:
|
||||
cost_matrix = -cost_matrix
|
||||
|
||||
minimum_cost = float("inf")
|
||||
|
||||
if h >= w:
|
||||
for i_idices in itertools.permutations(list(range(h)), min(h, w)):
|
||||
row_ind = i_idices # non-diag (x,y)s
|
||||
col_ind = list(range(w))
|
||||
cost = cost_matrix[row_ind, col_ind].sum()
|
||||
if cost < minimum_cost:
|
||||
minimum_cost = cost
|
||||
optimal_row_ind = row_ind
|
||||
optimal_col_ind = col_ind
|
||||
if h < w:
|
||||
for j_idices in itertools.permutations(list(range(w)), min(h, w)):
|
||||
row_ind = list(range(h))
|
||||
col_ind = j_idices
|
||||
cost = cost_matrix[row_ind, col_ind].sum()
|
||||
if cost < minimum_cost:
|
||||
minimum_cost = cost
|
||||
optimal_row_ind = row_ind
|
||||
optimal_col_ind = col_ind
|
||||
|
||||
return optimal_row_ind, list(optimal_col_ind)
|
||||
|
||||
|
||||
def linear_sum_assignment_hungarian(cost_matrix, maximize=False):
|
||||
"""
|
||||
Get the element position
|
||||
cost_matrix: array of boolean
|
||||
if maximize=True, please change to profit_matrix instead
|
||||
"""
|
||||
|
||||
if cost_matrix.shape[0] == 1 and cost_matrix.shape[1] == 1:
|
||||
return [0], [0]
|
||||
cost_matrix = np.multiply(np.array(cost_matrix), 1)
|
||||
h, w = cost_matrix.shape[0], cost_matrix.shape[1]
|
||||
cur_mat = cost_matrix
|
||||
|
||||
#Step 1 - Every column and every row subtract its internal minimum
|
||||
zero_count = 0
|
||||
if h > w:
|
||||
min_dim = w
|
||||
while zero_count < min_dim:
|
||||
#Step 2 & 3
|
||||
ans_pos, marked_rows, marked_cols = mark_matrix(cur_mat)
|
||||
zero_count = len(marked_rows) + len(marked_cols)
|
||||
|
||||
if zero_count < min_dim:
|
||||
cur_mat = adjust_matrix(cur_mat, marked_rows, marked_cols)
|
||||
else:
|
||||
min_dim = h
|
||||
while zero_count < min_dim:
|
||||
#Step 2 & 3
|
||||
ans_pos, marked_rows, marked_cols = mark_matrix(cur_mat, min_w=False)
|
||||
zero_count = len(marked_rows) + len(marked_cols)
|
||||
|
||||
if zero_count < min_dim:
|
||||
cur_mat = adjust_matrix(cur_mat, marked_rows, marked_cols)
|
||||
optimal_row_ind = [x[0] for x in ans_pos]
|
||||
optimal_col_ind = [x[1] for x in ans_pos]
|
||||
|
||||
indices = np.argsort(np.array(optimal_row_ind), kind='mergesort')
|
||||
optimal_row_ind = np.array(optimal_row_ind)[indices]
|
||||
optimal_col_ind = np.array(optimal_col_ind)[indices]
|
||||
return optimal_row_ind, optimal_col_ind
|
||||
|
||||
|
||||
def min_zero_row(zero_mat, mark_zero):
|
||||
'''
|
||||
The function can be splitted into two steps:
|
||||
#1 The function is used to find the row which containing the fewest 0.
|
||||
#2 Select the zero number on the row, and then marked the element corresponding row and column as False
|
||||
'''
|
||||
#Find the row
|
||||
min_row = [99999, -1]
|
||||
|
||||
for row_num in range(zero_mat.shape[0]):
|
||||
if np.sum(zero_mat[row_num] == 1) > 0 and min_row[0] > np.sum(zero_mat[row_num] == 1):
|
||||
min_row = [np.sum(zero_mat[row_num] == 1), row_num]
|
||||
|
||||
# Marked the specific row and column as False
|
||||
zero_index = np.where(zero_mat[min_row[1]] == 1)[0][0]
|
||||
mark_zero.append((min_row[1], zero_index))
|
||||
zero_mat[min_row[1], :] = False
|
||||
zero_mat[:, zero_index] = False
|
||||
|
||||
|
||||
def min_zero_col(zero_mat, mark_zero):
|
||||
'''
|
||||
The function can be splitted into two steps:
|
||||
#1 The function is used to find the row which containing the fewest 0.
|
||||
#2 Select the zero number on the row, and then marked the element corresponding row and column as False
|
||||
'''
|
||||
#Find the row
|
||||
min_col = [99999, -1]
|
||||
|
||||
for col_num in range(zero_mat.shape[1]):
|
||||
if np.sum(zero_mat[:, col_num] == 1) > 0 and min_col[0] > np.sum(zero_mat[:, col_num] == 1):
|
||||
min_col = [np.sum(zero_mat[:, col_num] == 1), col_num]
|
||||
|
||||
# Marked the specific row and column as False
|
||||
zero_index = np.where(zero_mat[:, min_col[1]] == 1)[0][0]
|
||||
mark_zero.append((zero_index, min_col[1]))
|
||||
zero_mat[:, min_col[1]] = False
|
||||
zero_mat[zero_index, :] = False
|
||||
|
||||
|
||||
def mark_matrix(mat, min_w=True):
|
||||
'''
|
||||
Finding the returning possible solutions for LAP problem.
|
||||
'''
|
||||
#Transform the matrix to boolean matrix(0 = True, others = False)
|
||||
cur_mat = mat
|
||||
zero_bool_mat = (cur_mat == 0)
|
||||
zero_bool_mat_copy = zero_bool_mat.copy()
|
||||
|
||||
#Recording possible answer positions by marked_zero
|
||||
marked_zero = []
|
||||
while (True in zero_bool_mat_copy):
|
||||
if min_w:
|
||||
min_zero_row(zero_bool_mat_copy, marked_zero)
|
||||
else:
|
||||
min_zero_col(zero_bool_mat_copy, marked_zero)
|
||||
|
||||
#Recording the row and column positions seperately.
|
||||
marked_zero_row = []
|
||||
marked_zero_col = []
|
||||
for i, marked_row in enumerate(marked_zero):
|
||||
marked_zero_row.append(marked_zero[i][0])
|
||||
marked_zero_col.append(marked_zero[i][1])
|
||||
|
||||
#Step 2-2-1
|
||||
non_marked_row = list(set(range(cur_mat.shape[0])) - set(marked_zero_row))
|
||||
|
||||
marked_cols = []
|
||||
check_switch = True
|
||||
while check_switch:
|
||||
check_switch = False
|
||||
for i, the_row in enumerate(non_marked_row):
|
||||
row_array = zero_bool_mat[the_row, :]
|
||||
for j in range(row_array.shape[0]):
|
||||
#Step 2-2-2
|
||||
if row_array[j] == 1 and j not in marked_cols:
|
||||
#Step 2-2-3
|
||||
marked_cols.append(j)
|
||||
check_switch = True
|
||||
|
||||
for row_num, col_num in marked_zero:
|
||||
#Step 2-2-4
|
||||
if row_num not in non_marked_row and col_num in marked_cols:
|
||||
#Step 2-2-5
|
||||
non_marked_row.append(row_num)
|
||||
check_switch = True
|
||||
#Step 2-2-6
|
||||
marked_rows = list(set(range(mat.shape[0])) - set(non_marked_row))
|
||||
|
||||
return marked_zero, marked_rows, marked_cols
|
||||
|
||||
|
||||
def adjust_matrix(mat, cover_rows, cover_cols):
|
||||
cur_mat = mat
|
||||
non_zero_element = []
|
||||
|
||||
#Step 4-1
|
||||
for row_i, cur_row in enumerate(cur_mat):
|
||||
if row_i not in cover_rows:
|
||||
for col_i, cur_col in enumerate(cur_mat[row_i]):
|
||||
if col_i not in cover_cols:
|
||||
non_zero_element.append(cur_mat[row_i][col_i])
|
||||
|
||||
min_num = min(non_zero_element)
|
||||
|
||||
#Step 4-2
|
||||
for row_i, cur_row in enumerate(cur_mat):
|
||||
if row_i not in cover_rows:
|
||||
for col_i, cur_col in enumerate(cur_mat[row_i]):
|
||||
if col_i not in cover_cols:
|
||||
cur_mat[row_i, col_i] = cur_mat[row_i, col_i] - min_num
|
||||
#Step 4-3
|
||||
for row, cover_row in enumerate(cover_rows):
|
||||
for col, cover_col in enumerate(cover_cols):
|
||||
cur_mat[cover_rows[row], cover_cols[col]] = cur_mat[cover_rows[row], cover_cols[col]] + min_num
|
||||
return cur_mat
|
||||
|
||||
|
||||
def _get_ap_prec_rec(rec, prec):
|
||||
# make sure the x-input to auc is sorted
|
||||
assert np.sum(np.diff(rec) >= 0) == len(rec) - 1
|
||||
# compute error matrices
|
||||
return _get_auc(rec, prec), _get_peakf1(rec, prec), _get_eer(rec, prec)
|
||||
|
||||
|
||||
def _get_auc(frp, trp):
|
||||
|
||||
x0, y0 = np.ravel(np.asarray(frp).reshape(-1)), np.ravel(np.asarray(trp).reshape(-1))
|
||||
|
||||
if x0.shape[0] < 2:
|
||||
raise ValueError(
|
||||
"Wrong shape! where x.shape = %s"
|
||||
% x0.shape
|
||||
)
|
||||
|
||||
direction = 1
|
||||
dx = np.diff(x0)
|
||||
if np.any(dx < 0):
|
||||
if np.all(dx <= 0):
|
||||
direction = -1
|
||||
else:
|
||||
raise ValueError("x is not in chronological order, please modify : {}.".format(x0))
|
||||
|
||||
area_under_curve = direction * np.trapz(y0, x0)
|
||||
if isinstance(area_under_curve, np.memmap):
|
||||
area_under_curve = area_under_curve.dtype.type(area_under_curve)
|
||||
return area_under_curve
|
||||
|
||||
|
||||
|
||||
def _get_peakf1(recs, precs):
|
||||
return np.max(2 * precs * recs / np.clip(precs + recs, 1e-16, 2 + 1e-16))
|
||||
|
||||
|
||||
def _get_eer(recs, precs):
|
||||
# Find the first nonzero or else (0,0) will be the EER :)
|
||||
def first_nonzero_element(arr):
|
||||
return np.where(arr != 0)[0][0]
|
||||
|
||||
p1 = first_nonzero_element(precs)
|
||||
r1 = first_nonzero_element(recs)
|
||||
idx = np.argmin(np.abs(precs[p1:] - recs[r1:]))
|
||||
return np.average([precs[p1 + idx], recs[r1 + idx]])
|
108
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/utils/utils.py
Normal file
108
2D_LiDAR_Pedestrain_Detection/LaserDet/srcs/utils/utils.py
Normal file
@@ -0,0 +1,108 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
import math
|
||||
import numpy as np
|
||||
|
||||
|
||||
|
||||
def xy_to_rphi(x, y):
|
||||
return np.hypot(x, y), np.arctan2(y, x)
|
||||
|
||||
|
||||
|
||||
def global_to_canonical(scan_r, scan_phi, dets_r, dets_phi):
|
||||
dx = np.sin(dets_phi - scan_phi) * dets_r
|
||||
dy = np.cos(dets_phi - scan_phi) * dets_r - scan_r
|
||||
return dx, dy
|
||||
|
||||
|
||||
def rphi_to_xy(r, phi):
|
||||
return r * np.cos(phi), r * np.sin(phi)
|
||||
|
||||
|
||||
def canonical_to_global(scan_r, scan_phi, dx, dy):
|
||||
y_shift = scan_r + dy
|
||||
phi_shift = np.arctan2(
|
||||
dx, y_shift
|
||||
)
|
||||
dets_phi = phi_shift + scan_phi
|
||||
dets_r = y_shift / np.cos(phi_shift)
|
||||
return dets_r, dets_phi
|
||||
|
||||
|
||||
|
||||
def trim_the_scans(
|
||||
scans,
|
||||
scan_phi,
|
||||
stride=1,
|
||||
win_width=1.66,
|
||||
win_depth=1.0,
|
||||
num_ct_pts=48,
|
||||
pad_val=29.99,
|
||||
):
|
||||
_pi = np.pi
|
||||
num_scans, num_pts = scans.shape
|
||||
|
||||
bisec_alp = np.arctan(0.5 * win_width / np.maximum(scans[:, ::stride], 1e-2))
|
||||
|
||||
# delta alpha
|
||||
del_alp = 2.0 * bisec_alp / (num_ct_pts - 1)
|
||||
ang_cutout = (
|
||||
scan_phi[::stride]
|
||||
- bisec_alp
|
||||
+ np.arange(num_ct_pts).reshape(num_ct_pts, 1, 1) * del_alp
|
||||
)
|
||||
ang_cutout = (ang_cutout + _pi) % (2.0 * _pi) - _pi
|
||||
inds_cutout = (ang_cutout - scan_phi[0]) / (scan_phi[1] - scan_phi[0])
|
||||
outter_mask = np.logical_or(inds_cutout < 0, inds_cutout > num_pts - 1)
|
||||
|
||||
# cutout (linear interp)
|
||||
inds_cutout_lower = np.core.umath.clip(np.floor(inds_cutout), 0, num_pts - 1).astype(np.int32)
|
||||
inds_cutout_upper = np.core.umath.clip(inds_cutout_lower + 1, 0, num_pts - 1).astype(np.int32)
|
||||
inds_ct_ratio = np.core.umath.clip(inds_cutout - inds_cutout_lower, 0.0, 1.0)
|
||||
|
||||
inds_offset = (np.arange(num_scans).reshape(1, num_scans, 1) * num_pts)
|
||||
cutout_lower = np.take(scans, inds_cutout_lower + inds_offset)
|
||||
cutout_upper = np.take(scans, inds_cutout_upper + inds_offset)
|
||||
ct0 = cutout_lower + inds_ct_ratio * (cutout_upper - cutout_lower)
|
||||
|
||||
|
||||
pt_dists = scans[:, ::stride]
|
||||
num_pts_win = inds_cutout[-1] - inds_cutout[0]
|
||||
area_mask = num_pts_win > num_ct_pts
|
||||
if np.sum(area_mask) > 0:
|
||||
sample_area = int(math.ceil(np.max(num_pts_win) / num_ct_pts))
|
||||
num_ct_pts_area = sample_area * num_ct_pts
|
||||
del_alp_area = 2.0 * bisec_alp / (num_ct_pts_area - 1)
|
||||
ang_ct_area = (
|
||||
scan_phi[::stride]
|
||||
- bisec_alp
|
||||
+ np.arange(num_ct_pts_area).reshape(num_ct_pts_area, 1, 1)
|
||||
* del_alp_area
|
||||
)
|
||||
ang_ct_area = (ang_ct_area + _pi) % (2.0 * _pi) - _pi # warp angle
|
||||
inds_ct_area = (ang_ct_area - scan_phi[0]) / (scan_phi[1] - scan_phi[0])
|
||||
inds_ct_area = np.rint(np.core.umath.clip(inds_ct_area, 0, num_pts - 1)).astype(np.int32)
|
||||
ct_area = np.take(scans, inds_ct_area + inds_offset)
|
||||
ct_area = ct_area.reshape(
|
||||
num_ct_pts, sample_area, num_scans, pt_dists.shape[1]
|
||||
).mean(axis=1)
|
||||
ct0[:, area_mask] = ct_area[:, area_mask]
|
||||
|
||||
|
||||
ct0[outter_mask] = pad_val
|
||||
ct1 = np.core.umath.clip(ct0, pt_dists - win_depth, pt_dists + win_depth)
|
||||
ct1 = (ct1 - pt_dists) / win_depth
|
||||
cutout_scan = np.ascontiguousarray(ct1.transpose((2, 1, 0)), dtype=np.float32)
|
||||
|
||||
return cutout_scan
|
643
2D_LiDAR_Pedestrain_Detection/README_cn.md
Normal file
643
2D_LiDAR_Pedestrain_Detection/README_cn.md
Normal file
@@ -0,0 +1,643 @@
|
||||
# 2D 激光雷达行人检测
|
||||
|
||||
## 1 介绍
|
||||
该项目基于DROW3和DR-SPAAM模型,实现了实时的2D激光雷达行人检测。 主要处理流程为:输入预处理后的激光雷达点云序列(帧)->行人检测模型推理->行人检测模型后处理->检测结果输出及可视化。
|
||||
|
||||
### 1.1 支持的产品
|
||||
|
||||
- Ascend 310
|
||||
- Atlas 200DK
|
||||
|
||||
### 1.2 支持的版本
|
||||
|
||||
Ascend-CANN:5.0.4
|
||||
SDK:2.0.4
|
||||
|
||||
### 1.3 软件方案介绍
|
||||
基于MindX SDK的2D激光雷达行人检测业务流程为:待检测LiDAR序列经预处理后得到按时间顺序的帧,输入本项目开发的模型推理插件,得到模型的推理结果。
|
||||
|
||||
表1.1 系统方案功能描述:
|
||||
序号 | 模块 | 功能
|
||||
--- | -----|-------
|
||||
1 | 序列处理 | 接收输入激光雷达点云序列路径,对序列进行处理,并将得到的帧存储到dataloader中,并发送到模型推理插件。
|
||||
2 | 模型推理 | 行人目标检测,输入为坐标转换后的帧,输出tensor为预测点分类结果和预测点坐标。
|
||||
3 | 行人检测后处理 | 实现对输入tensor解析,提取最终行人位置坐标。
|
||||
4 | 行人检测可视化 | 将后处理得到的每一帧的检测目标可视化,并显示在2D平面上。
|
||||
|
||||
|
||||
### 1.4 代码目录结构与说明
|
||||
|
||||
本工程提供的测试数据集目录如下:
|
||||
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── dataset
|
||||
│ ├── DROWv2
|
||||
│ │ ├── test
|
||||
│ │ ├── train
|
||||
│ │ ├── val
|
||||
│ ├── JRDB
|
||||
│ │ ├── test_dataset
|
||||
│ │ ├── train_dataset
|
||||
...
|
||||
```
|
||||
本工程目录如下:
|
||||
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── README_cn.md
|
||||
├── lidar_quicktest.sh
|
||||
├── lidar_submit.sh
|
||||
├── release_lidar_main.py
|
||||
├── release_lidar_speedtest.py
|
||||
│ ├── result.png
|
||||
├── LaserDet
|
||||
│ ├── dr_spaam_ros
|
||||
│ │ ├── src
|
||||
│ │ │ ├── dr_spaam_ros
|
||||
│ │ │ │ ├── launch
|
||||
│ │ │ │ │ ├── dr_spaam_ros.launch
|
||||
│ │ │ │ ├── scripts
|
||||
│ │ │ │ │ ├── drow_data_converter.py
|
||||
│ │ │ │ ├── __init__.py
|
||||
│ │ │ │ ├── CMakeLists.txt
|
||||
│ │ │ │ ├── dr_spaam_ros.py
|
||||
│ │ │ │ ├── node.py
|
||||
│ │ │ │ ├── package.xml
|
||||
│ │ │ │ ├── setup.py
|
||||
│ │ ├── example.rviz
|
||||
│ ├── scripts
|
||||
│ │ ├── det.py
|
||||
│ │ ├── eval_external.py
|
||||
│ │ ├── onnx_om_convertor.sh
|
||||
│ │ ├── setup_jrdb_dataset.py
|
||||
│ ├── srcs
|
||||
│ │ ├── data_handle
|
||||
│ │ │ ├── __init__.py
|
||||
│ │ │ ├── drow_handle.py
|
||||
│ │ │ ├── jrdb_handle_handle.py
|
||||
│ │ ├── data_loader
|
||||
│ │ │ ├── __init__.py
|
||||
│ │ │ ├── builder.py
|
||||
│ │ │ ├── drow_dataset.py
|
||||
│ │ │ ├── jrdb_dataset.py
|
||||
│ │ ├── nexts
|
||||
│ │ │ ├── __init__.py
|
||||
│ │ │ ├── dr_spaam.py
|
||||
│ │ │ ├── drow_net.py
|
||||
│ │ │ ├── get_model.py
|
||||
│ │ ├── utils
|
||||
│ │ │ ├── __init__.py
|
||||
│ │ │ ├── precision_recall.py
|
||||
│ │ │ ├── utils.py
|
||||
│ │ ├── __init__.py
|
||||
│ │ ├── detector.py
|
||||
│ ├── outputs_{*}
|
||||
│ ├── pipelines
|
||||
│ │ ├── *.pipeline
|
||||
│ ├── release_logs
|
||||
|
||||
```
|
||||
|
||||
### 1.5 技术实现流程图
|
||||
|
||||
DROW/DR-SPAAM模型前处理流程为:
|
||||
- 读取输入激光雷达点阵序列,根据预设的参数对序列进行裁剪和变换,得到原始模型支持的输入格式。
|
||||
- 得到的模型输入按时间顺序排列。
|
||||
|
||||
后处理插件的整体思路为:
|
||||
- 读取模型推理插件输出的帧中行人的位置信息,对位置信息进行坐标变换。
|
||||
- 进行NMS,通过空间距离作为两个点是否重合的度量标准,给定最小距离冗余阈值,移除可能重复检测点,提高置信度。
|
||||
|
||||
### 1.6 适应场景
|
||||
|
||||
本案例可实现2D激光雷达行人检测,对输入有以下限制:
|
||||
- 模型训练使用的数据为225 deg/360 deg,精度为0.5 deg,若采用其他测试样例,需额外增加补零或裁剪操作。
|
||||
- 输入要求为txt格式,其中.txt存储内容为float32数据类型。
|
||||
- 适用于单帧输入。
|
||||
|
||||
## 2 环境依赖
|
||||
|
||||
名称 | 版本 (310适用)
|
||||
------- | --------
|
||||
MindX SDK | 2.0.4
|
||||
Ubuntu | 18.0.4 LTS
|
||||
Ascend-CANN-toolkit | 5.0.4
|
||||
Python | 3.9.2
|
||||
|
||||
在编译运行项目前,先设置环境变量:
|
||||
|
||||
>``` bash
|
||||
> # please create your own set_env.sh
|
||||
>export MX_SDK_HOME="${PATH_TO_MX_SDK}/MindX_SDK/mxVision"
|
||||
>export LD_LIBRARY_PATH=${MX_SDK_HOME}/lib:${MX_SDK_HOME}/opensource/lib:/usr/local/Ascend/ascend-toolkit/latest/acllib/lib64:/usr/local/Ascend/driver/lib64/
|
||||
>export GST_PLUGIN_SCANNER=${MX_SDK_HOME}/opensource/libexec/gstreamer-1.0/gst-plugin-scanner
|
||||
>export GST_PLUGIN_PATH=${MX_SDK_HOME}/opensource/lib/gstreamer-1.0:${MX_SDK_HOME}/lib/plugins
|
||||
>export PYTHONPATH=${MX_SDK_HOME}/python
|
||||
>export PYTHONPATH=$PYTHONPATH:${PROJECT_PATH}/dr_spaam
|
||||
>```
|
||||
|
||||
方便起见,环境变量设置部分可以在运行的lidar_*.sh文件中找到。
|
||||
|
||||
## 3 软件依赖
|
||||
|
||||
如需要生成自己的数据集,涉及的第三方软件依赖如下:
|
||||
软件 | 版本 | 功能描述
|
||||
------- | -------- | --------
|
||||
json | NA | 读写.json文件。
|
||||
rosbag | 1.15.11 | 读取.bag格式的激光数据。
|
||||
roslz4 | 4.0.2 | To solve "Failed to load Python extension for LZ4 support. LZ4 compression will not be available." rosbag正常运行依赖之一。
|
||||
python-lzf | 0.2.4 | 压缩/解压缩.pcd格式的点云数据。
|
||||
|
||||
|
||||
## 4 模型转换
|
||||
|
||||
本项目使用的模型checkpoints可通过[here](
|
||||
https://mindx.sdk.obs.cn-north-4.myhuaweicloud.com/ascend_community_projects/2D_lidar_pedestrian_target_detection/Archive_pth_om_petit.zip)获取。压缩文件下载后解压,checkpoints文件后缀是.pth,下载后先将checkpoints转换成onnx格式,再使用模型转换工具[ATC](https://support.huaweicloud.com/tg-cannApplicationDev330/atlasatc_16_0005.html)将onnx转换成om模型。
|
||||
|
||||
### 4.1 DROW3 模型转换
|
||||
|
||||
<em>4.1.1 checkpoint文件转onnx文件</em>
|
||||
|
||||
将.pth模型下载并解压到(PROJECT_PATH)/dr\_spaam/ckpts/路径下,修改(PROJECT_PATH)/LaserDet/scripts/det.py代码中的参数ckpt,model,和panoramic_scan。模型名称model应与ckpt对应。
|
||||
需要修改的参数共计6个,即
|
||||
- 类Detector()中的ckpt_path: {PATH_TO_UNZIPPED_CHECKPOINTS}
|
||||
- 类Detector()中的dataset: "DROW"或"JRDB"
|
||||
- 类Detector()中的model: "DROW3"或"DR-SPAAM
|
||||
- 类Detector()中的panoramic_scan: 如果数据集为DROWv2,则panoramic\_scan=False;如果数据集为JRDB,则panoramic\_scan=True。
|
||||
- num_pts:
|
||||
- torch.onnx.export()中的第三个参数,即输出onnx的文件名
|
||||
|
||||
为了简化执行步骤,前往det.py文件所在路径,执行以下步骤:
|
||||
```
|
||||
$ cd ${PATH_TO_PROJECT}/LaserDet/scripts
|
||||
# activate any torch env
|
||||
# make sure you check the args, ckpt, model, and panoramic_scan, of class Detector in det.py
|
||||
$ python det.py --ckpt_path ${PATH_TO_UNZIPPED_CHECKPOINTS}
|
||||
```
|
||||
该步骤后,生成的onnx默认保存在当前文件夹下。
|
||||
|
||||
|
||||
<em>4.1.2 onnx文件转om文件</em>
|
||||
|
||||
进入onnx所在文件夹,执行以下步骤:
|
||||
```
|
||||
$ atc --model=$(PATH_TO_YOUR_DROW3_ONNX)/(DROW_MODEL_NAME).onnx --framework=5 --output={OUTPUT_NAME} -soc_version=Ascend310
|
||||
```
|
||||
生成的文件模型 *.om一般默认保存在当前执行命令所在路径下。执行后终端输入为:
|
||||
```
|
||||
ATC run success, welcome to the next use.
|
||||
```
|
||||
表示模型转换流程完成。
|
||||
|
||||
### 4.2 DR-SPAAM 模型转换
|
||||
|
||||
<em>4.2.1 checkpoint文件转onnx文件</em>
|
||||
|
||||
同4.1.1,前往det.py文件所在路径,执行以下步骤:
|
||||
```
|
||||
$ cd ${PATH_TO_PROJECT}/LaserDet/scripts
|
||||
# activate any torch env
|
||||
# make sure you check the args, ckpt, model, and panoramic_scan, of class Detector in det.py
|
||||
$ python det.py --ckpt_path ${PATH_TO_UNZIPPED_CHECKPOINTS}
|
||||
```
|
||||
|
||||
<em>4.2.2 onnx文件转om文件</em>
|
||||
进入onnx所在文件夹,执行以下步骤:
|
||||
>``` bash
|
||||
># onnx_om_convertor.sh
|
||||
>atc --model=$(PATH_TO_YOUR_DR_SPAAM_ONNX)/(DR_SPAAM_MODEL_NAME).onnx --framework=5 --output={OUTPUT_NAME} -soc_version=Ascend310
|
||||
>```
|
||||
|
||||
生成的文件模型 *.om一般默认保存在当前执行命令所在路径下。执行后终端输入为:
|
||||
```
|
||||
ATC run success, welcome to the next use.
|
||||
```
|
||||
表示模型转换流程完成。
|
||||
|
||||
## 5 准备
|
||||
### 5.1 数据集准备
|
||||
<em>5.1.1 下载测试数据集</em>
|
||||
|
||||
创建dataset目录,确保下载并解压完毕后的dataset目录结构为
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── dataset
|
||||
│ ├── DROWv2
|
||||
│ │ ├── test
|
||||
│ │ ├── train
|
||||
│ │ ├── val
|
||||
│ ├── JRDB
|
||||
│ │ ├── test_dataset
|
||||
│ │ ├── train_dataset
|
||||
...
|
||||
```
|
||||
数据集下载地址:
|
||||
- [DROW dataset](https://github.com/VisualComputingInstitute/DROW)
|
||||
- [JackRabbot dataset](https://jrdb.stanford.edu/)
|
||||
|
||||
<em>5.1.2 预处理 JRDB 数据集</em>
|
||||
|
||||
即将激光测量数据从RAW格式的rosbag中提取出来,并且按时间轴与摄像头获取的图像对其,执行以下步骤:
|
||||
```
|
||||
# install required dependencies
|
||||
$ pip install python-lzf
|
||||
$ pip install lz4
|
||||
$ pip install --extra-index-url https://rospypi.github.io/simple/ rosbag
|
||||
$ pip install roslz4 --extra-index-url https://rospypi.github.io/simple/
|
||||
# extract laser measurements from raw rosbag and synchronize with images
|
||||
$ python bin/setup_jrdb_dataset.py
|
||||
```
|
||||
|
||||
### 5.2 pipeline文件准备
|
||||
本项目提供了四个pipeline文件以满足测试要求,请将pipelines文件保存在以下路径。
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── pipelines
|
||||
│ ├── dr_spaam_drow_e40.pipeline
|
||||
│ ├── dr_spamm_jrdb_e20.pipeline
|
||||
│ ├── drow3_drow_e40.pipeline
|
||||
│ ├── drow3_jrdb_e20.pipeline
|
||||
...
|
||||
```
|
||||
其中DROWv2数据集对应的pipeline文件为dr_spaam_e40.pipeline和drow_e40.pipeline,JRDB数据集对应的pipeline文件为drow_jrdb_e20.pipeline和dr_spaam_jrdb_e20.pipeline。 确保pipeline文件中模型推理插件**mxpi_tensorinfer**的参数["props"]["model_path"]是正确的。
|
||||
|
||||
## 6 编译与运行
|
||||
S1. 按 __2 环境依赖__ 中的步骤设置环境变量。
|
||||
|
||||
S2. 按 __4 模型转换__ 中的步骤获得om模型推理文件,并按 __5.2 pipeline文件准备__ 中的步骤确认模型推理文件是否可以被正确调用。
|
||||
|
||||
S3. 按 __5.1 数据集准备__ 中的步骤准备测试用数据集。
|
||||
|
||||
S4. 运行行人检测推理。首先找到可执行文件所在路径,在当前项目根目录下。
|
||||
```
|
||||
$ cd $(PROJECT_PATH)
|
||||
```
|
||||
命令执行成功后,终端打印出测试精度,并将可视化结果保存在项目根目录下。关于测试文件的使用方法详见 __7 性能与精度测试__
|
||||
|
||||
## 7 性能与精度测试
|
||||
|
||||
### 7.1 性能测试
|
||||
执行 __6 编译与运行__ 中 S1-S3步骤完成准备工作,执行以下命令:
|
||||
首先确保lidar_quicktest.sh中的python命令行如下:
|
||||
>```bash
|
||||
> # lidar_quicktest.sh
|
||||
>nohup python -u release_lidar_speedtest.py --data_path $1 --pipe_store $2 --split $3 --seq_name $4
|
||||
>```
|
||||
[^注] 当测试完整数据集时,split可以为val/test;当测试单个序列时,split可以为train_nano/test_nano;当测试单个帧时,split可以为train_single/test_single。对于DROWv2数据集,序列名称即为train/test文件夹下.csv文件的名称;对于JRDB数据集,序列名称可以在train_dataset/lasers或test_dataset/lasers下快速查找得到。
|
||||
|
||||
测试整个数据集的平均性能:
|
||||
>```bash
|
||||
> # lidar_quicktest.sh
|
||||
>nohup python -u release_lidar_speedtest.py --data_path $1 --pipe_store $2 --split $3
|
||||
>```
|
||||
```
|
||||
$ cd $(PROJECT_PATH)
|
||||
$ bash lidar_quicktest.sh dataset/{DATASET_NAME} pipelines/{NAME.pipeline} {VAL_OR_TEST}
|
||||
# e.g. bash lidar_quicktest.sh dataset/DROWv2 pipelines/drow3_drow_e40.pipeline val
|
||||
# e.g. bash lidar_quicktest.sh dataset/DROWv2 pipelines/dr_spaam_drow_e40.pipeline val
|
||||
# e.g. bash lidar_quicktest.sh dataset/JRDB pipelines/drow3_jrdb_e40.pipeline val
|
||||
# e.g. bash lidar_quicktest.sh dataset/JRDB pipelines/dr_spaam_jrdb_e40.pipeline val
|
||||
```
|
||||
经测试,推理性能可达到如下表所示,满足性能要求。实际推理速度与输入帧每一行的点数、数据集的大小有关,同时也与CPU的可分配资源有关。
|
||||
该命令不包含可视化输出。
|
||||
|
||||
On DROW val dataset (450 points, 225 degrees field of view)
|
||||
| | FPS (Ascend 310) |
|
||||
|--------|------------------|
|
||||
|DROW3 | 6.6274 |
|
||||
|DR-SPAAM| 3.0385 |
|
||||
|
||||
[^注] 因为预处理方式不同,DR-SPAAM模型的输入是DROW3的十倍,模型本身体量差异不大,执行性能体现在FPS上。
|
||||
|
||||
On JackRabbot (JRDB) val dataset (1091 points, 360 degrees field of view)
|
||||
| | FPS (Ascend 310) |
|
||||
|--------|------------------|
|
||||
|DROW3 | 11.0865 |
|
||||
|DR-SPAAM| 10.9769 |
|
||||
|
||||
[^注] JRDB数据集的性能测试不包括计算精度的时间。
|
||||
|
||||
### 7.2 精度测试
|
||||
|
||||
执行 __6 编译与运行__ 中 S1-S3步骤完成准备工作。
|
||||
|
||||
<em>7.2.1 DROWv2数据集测试</em>
|
||||
|
||||
** 基于序的评价指标 **
|
||||
|
||||
* AP (ROC curve 与 AUC):将所有的样本-标签对按照预测值逆序排列,从坐标点$(0,0)$出发,若第1个为正,则向上走一步,否则向右走一步,向上走一步的步距为$1/P$,向右走一步的步距为$1/N$,其中$|P|$为实际正标签的的总数,$|N|$为实际负标签的的总数。这样获得的曲线称为ROC(Receiver Operating Characteristic Curve),而AUC(Area Under Curve)就是该曲线与坐标轴围成的面积。本项目的测试指标AP即AUC。
|
||||
|
||||
* peak-F1:将所有的样本-标签对按照预测值逆序排列,第$k$次认为前$k$个样本-标签对为正,以此画出F1曲线,最终取该曲线中最大值,称之为peak-F1.
|
||||
|
||||
* EER:均等错误率EER(Equal Error Rate)是ROC曲线中FPR+TPR==1.0的地方,即ROC曲线与经过点$(1,0)$和点$(0,1)$的直线的交点。
|
||||
|
||||
若选择测试数据集为DROWv2,执行命令后终端输出测试精度。
|
||||
首先确保lidar_submit.sh中的python命令行的输入如下:
|
||||
>```bash
|
||||
> # lidar_submitt.sh
|
||||
>nohup python -u release_lidar_main.py --data_path $1 --pipe_store $2 --split $3 --visu $4
|
||||
>```
|
||||
再执行如下
|
||||
```
|
||||
$ cd $(PROJECT_PATH)
|
||||
$ bash lidar_submit.sh dataset/DROWv2 pipelines/{NAME.pipeline} {VAL_OR_TEST} {True or False}
|
||||
# e.g. bash lidar_submit.sh dataset/DROWv2 pipelines/drow3_drow_e40.pipeline test False
|
||||
# e.g. bash lidar_submit.sh dataset/DROWv2 pipelines/drow3_drow_e40.pipeline val False
|
||||
# e.g. bash lidar_submit.sh dataset/DROWv2 pipelines/dr_spaam_drow_e40.pipeline test False
|
||||
# e.g. bash lidar_submit.sh dataset/DROWv2 pipelines/dr_spaam_drow_e40.pipeline val False
|
||||
```
|
||||
On DROW test dataset (450 points, 225 degrees field of view)
|
||||
| | AP<sub>0.3</sub> | AP<sub>0.5</sub> | peak_F1<sub>0.3</sub> | peak_F1<sub>0.5</sub> | EER<sub>0.3</sub> | EER<sub>0.5</sub> |
|
||||
|--------|------------------|------------------|-----------------------|------------------|-----------------------|------------------|
|
||||
|DROW3 (GPU) | 0.6375 | 0.6589 | 0.6431 | 0.6505 | 0.6407 | 0.6483 |
|
||||
|DROW3 (310) | 0.6374 | 0.6586 | 0.6427 | 0.6502 | 0.6586 | 0.6478 |
|
||||
|DR-SPAAM (GPU)| 0.7072 | 0.7227 | 0.6941 | 0.6979 | 0.6822 | 0.6878 |
|
||||
|DR-SPAAM (310)| 0.7092 | 0.7250 | 0.6970 | 0.7010 | 0.6862 | 0.6918 |
|
||||
|
||||
On DROW val dataset (450 points, 225 degrees field of view)
|
||||
| | AP<sub>0.3</sub> | AP<sub>0.5</sub> | peak_F1<sub>0.3</sub> | peak_F1<sub>0.5</sub> | EER<sub>0.3</sub> | EER<sub>0.5</sub> |
|
||||
|--------|------------------|------------------|-----------------------|------------------|-----------------------|------------------|
|
||||
|DROW3 (GPU) | 0.4346 | 0.4507 | 0.4953 | 0.5024 | 0.4932 | 0.5000 |
|
||||
|DROW3 (310) | 0.4347 | 0.4503 | 0.4949 | 0.5023 | 0.4929 | 0.4997 |
|
||||
|DR-SPAAM (GPU)| 0.5107 | 0.5284 | 0.5476 | 0.5552 | 0.5458 | 0.5535 |
|
||||
|DR-SPAAM (310)| 0.5128 | 0.5297 | 0.5488 | 0.5560 | 0.5474 | 0.5551 |
|
||||
|
||||
[^注] DROWv2数据集的val部分比test部分包含更多hard samples,故两个推理模型的val检测结果比test检测结果差。
|
||||
|
||||
<em>7.2.2 JRDB数据集测试</em>
|
||||
|
||||
若选择测试数据集为JRDB,因计算精度时几何增加的运算复杂度,执行命令后会将检测结果保存在路径下,需要切换测试环境(任意支持scipy和sklearn依赖的环境)以获得最终测试精度。首先执行以下命令
|
||||
```
|
||||
$ cd $(PROJECT_PATH)
|
||||
$ bash lidar_submit.sh dataset/JRDB pipelines/{NAME.pipeline} {VAL_OR_TEST} False
|
||||
# e.g. bash lidar_submit.sh dataset/JRDB pipelines/drow3_jrdb_e40.pipeline test False
|
||||
# e.g. bash lidar_submit.sh dataset/JRDB pipelines/dr_spaam_jrdb_e40.pipeline test False
|
||||
# e.g. bash lidar_submit.sh dataset/JRDB pipelines/drow3_jrdb_e40.pipeline val False
|
||||
# e.g. bash lidar_submit.sh dataset/JRDB pipelines/dr_spaam_jrdb_e40.pipeline val False
|
||||
```
|
||||
默认的检测结果和对应的groundtruth将会被保存到$(PROJECT_PATH)/outputs_{MODEL_NAME}_JRDB/下,保存的结果如下所示:
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── output_JRDB_{MODEL_NAME}
|
||||
│ ├── detections
|
||||
│ │ ├── <sequence_name_0>
|
||||
│ │ │ ├── 000000.txt
|
||||
│ │ │ ├── 000001.txt
|
||||
│ │ │ ├── ...
|
||||
│ │ ├── <sequence_name_1>
|
||||
│ │ │ ├── 000000.txt
|
||||
│ │ │ ├── 000001.txt
|
||||
│ │ │ ├── ...
|
||||
│ ├── groundtruth
|
||||
│ │ ├── <sequence_name_0>
|
||||
│ │ │ ├── 000000.txt
|
||||
│ │ │ ├── 000001.txt
|
||||
│ │ │ ├── ...
|
||||
│ │ ├── <sequence_name_1>
|
||||
│ │ │ ├── 000000.txt
|
||||
│ │ │ ├── 000001.txt
|
||||
│ │ │ ├── ...
|
||||
...
|
||||
```
|
||||
如果测试单个序列,保存路径有少许不同,如下
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── output_JRDB_{seq_name}_{MODEL_NAME}
|
||||
│ ├── detections
|
||||
│ │ ├── 000000.txt
|
||||
│ │ ├── 000001.txt
|
||||
│ │ ├── ...
|
||||
│ ├── groundtruth
|
||||
│ │ ├── 000000.txt
|
||||
│ │ ├── 000001.txt
|
||||
│ │ ├── ...
|
||||
```
|
||||
确认输出结果存在后,可在支持[scipy](https://new.scipy.org/install.html)和[sklearn](https://scikit-learn.org/stable/install.html)的环境中安装依赖。注意安装顺序,首先安装numpy和scipy,再安装sklearn:
|
||||
```
|
||||
# # If using pip
|
||||
# To install scipy, try:
|
||||
$ pip install scipy
|
||||
# If this fails, then try:
|
||||
$ python -m pip install --user numpy scipy matplotlib ipython jupyter pandas sympy nose
|
||||
# To install sklearn, try:
|
||||
$ pip install -U scikit-learn
|
||||
|
||||
# # If using conda
|
||||
$ conda install -c anaconda scipy
|
||||
$ conda install -c anaconda scikit-learn
|
||||
```
|
||||
我们提供了可供参考的脚本LaserDet/scripts/eval_external.py:
|
||||
|
||||
将参数 --result_dir 修改为正确的输出结果txt集地址,执行以下指令:
|
||||
|
||||
```
|
||||
$ cd $(PROJECT_PATH)/LaserDet
|
||||
$ python scripts/eval_external.py --result_dir ${OUTPUTS_RESULTS_DIR}
|
||||
```
|
||||
执行命令后终端输出测试精度。
|
||||
|
||||
On JackRabbot(JRDB) test dataset (1091 points, 360 degrees field of view)
|
||||
| | AP<sub>0.3</sub> | AP<sub>0.5</sub> | peak_F1<sub>0.3</sub> | peak_F1<sub>0.5</sub> | EER<sub>0.3</sub> | EER<sub>0.5</sub> |
|
||||
|--------|------------------|------------------|-----------------------|------------------|-----------------------|------------------|
|
||||
|DROW3 (GPU) | 0.7642 | 0.8255 | 0.7277 | 0.7516 | 0.7229 | 0.7479 |
|
||||
|DROW3 (310) | 0.7357 | 0.8170 | 0.7138 | 0.7468 | 0.7096 | 0.7344 |
|
||||
|DR-SPAAM (GPU) | 0.7856 | 0.8377 | 0.7482 | 0.7744 | 0.7477 | 0.7741 |
|
||||
|DR-SPAAM (310) | 0.7560 | 0.8289 | 0.7320 | 0.7677 | 0.7311 | 0.7673 |
|
||||
|
||||
[^注] 验证DROWv2和JRDB的精度值不能跨数据集比较。
|
||||
|
||||
### 7.2 可视化测试
|
||||
需要提前安装安装matplotlib。运行脚本 lidar_submit.sh 时,在该script中的指令中加上--visu True (示例中,--visu为bash命令的第四个arg)。安装matplotlib命令如下:
|
||||
```
|
||||
$ pip3 install matplotlib
|
||||
```
|
||||
确保lidar_submit.sh的python命令行修改如下,本例设置了6个外部输入变量。
|
||||
>``` bash
|
||||
> # lidar_submit.sh
|
||||
>python -u release_lidar_main.py --data_path $1 --pipe_store $2 --split $3 --visu $4 --seq_name $5 --frame_id $6
|
||||
>```
|
||||
|
||||
执行命令:
|
||||
$ bash lidar_submit.sh \
|
||||
$(path_to_dataset)/dataset/JRDB \ # Dataset: JRDB
|
||||
$(path_to_pipeline)/pipelines/drow3_jrdb_e40.pipeline \ # Model name: DROW3 Or DR-SPAAM
|
||||
train_single \
|
||||
True \
|
||||
cubberly-auditorium-2019-04-22_0 \
|
||||
1234
|
||||
|
||||
可视化结果将保存在项目根目录的./fig文件下。
|
||||
```
|
||||
$(PROJECT_DIR)
|
||||
├── figs
|
||||
│ ├── sequence_name01
|
||||
│ │ ├── dddddd.png
|
||||
│ │ ├── dddddd.png
|
||||
│ │ ├── ...
|
||||
│ ├── sequence_name02
|
||||
│ │ ├── dddddd.png
|
||||
│ │ ├── dddddd.png
|
||||
│ │ ├── ...
|
||||
```
|
||||
|
||||

|
||||
|
||||
## 8 ROS环境下的测试
|
||||
|
||||
### 8.1 Altas 200dk 开发板 ROS环境配置
|
||||
|
||||
材料清单:
|
||||
|
||||
|名称 | 数量 |
|
||||
|--------|------------------|
|
||||
| Atlas-200dk开发板+配套电源线 | 1 |
|
||||
| Type-C USB线 | 1 |
|
||||
| 网线 | 1 |
|
||||
| 可共享网络的设备(如电脑或路由器) | 1 |
|
||||
| SD卡(建议100G以上) | 1 |
|
||||
| 读卡器 | 1 |
|
||||
|
||||
请参阅[Atlas200dk-MindXSDK开发环境搭建一站式导航](https://gitee.com/ascend/docs-openmind/blob/master/guide/mindx/ascend_community_projects/tutorials/200dk%E5%BC%80%E5%8F%91%E6%9D%BF%E7%8E%AF%E5%A2%83%E6%90%AD%E5%BB%BA.md#https://gitee.com/link?target=https%3A%2F%2Fwww.hiascend.com%2Fzh%2Fsoftware%2Fmindx-sdk%2FmxVision%2Fcommunity%25EF%25BC%258C%25E9%2580%2589%25E6%258B%25A9arrch64%25E6%259E%25B6%25E6%259E%2584%25EF%25BC%258C%25E4%25B8%258B%25E8%25BD%25BDAscend-mindxsdk-mxvision_2.0.4_linux-aarch64.run)在Atlas200dk开发板或同类型平台上安装好MindXSDK。[确认python版本>3.6]
|
||||
|
||||
请参阅[Atlas200dk-ROS系统移植一站式导航](https://gitee.com/ascend/docs-openmind/blob/master/guide/mindx/ascend_community_projects/tutorials/200dk-ROS%E7%B3%BB%E7%BB%9F%E7%A7%BB%E6%A4%8D.md)在Atlas200dk开发板或同类型平台上安装好ROS系统。[确认ros melodic==1.14.13]
|
||||
|
||||
考虑到Atlas-200dk无可视化操作界面,测试结果需要借助其他平台展示,如有可视化操作界面的Linux系统,安装版本为desktop系列,windows系统下请安装虚拟机,再在虚拟机中配置Linux下的ROS系统。
|
||||
|
||||
### 8.2 编译与运行
|
||||
|
||||
#### 8.2.1 编译ROS节点
|
||||
|
||||
首先为执行cmake新建一个文件夹,并命名为dr_spaam_ros(原git clone项目下的dr_spaam_ros文件夹改名为dr_spaam_ros_backup或其他不冲突的名称)。
|
||||
```
|
||||
$ cd $(PATH_TO_LaserDet)
|
||||
$ mkdir -p dr_spaam_ros
|
||||
$ cd dr_spaam_ros
|
||||
$ catkin_make
|
||||
// This will create a build folder and a devel folder
|
||||
$ catkin_make_isolated
|
||||
// This will create a build_isolated folder and a devel_isolated folder
|
||||
// a CMakeLists.txt file will appear under the src folder
|
||||
```
|
||||
|
||||
完成后,dr_spaam_ros路径下应有如下:
|
||||
```
|
||||
$(LaserDet)
|
||||
├── dr_spaam_ros
|
||||
│ ├── build
|
||||
│ │ ├── ...
|
||||
│ ├── build_isolated
|
||||
│ │ ├── ...
|
||||
│ ├── devel
|
||||
│ │ ├── ...
|
||||
│ ├── devel_isolated
|
||||
│ │ ├── ...
|
||||
│ ├── src
|
||||
│ │ ├── ...
|
||||
│ │ ├── CMakeLists.txt
|
||||
│ ├── .catkin_workspace
|
||||
│ ├── example.rviz
|
||||
```
|
||||
|
||||
#### 8.2.2 运行ROS节点
|
||||
|
||||
我们假设读者已正常执行步骤1-7,所需模型与数据集已就位。默认在ROS环境下,每开启一个新的终端都在路径$(PATH_TO_LASERDET)/LaserDet/dr_spaam_ros下,并执行source devel/setup.bash添加ROS环境路径。至目前该ROS节点支持JRDB数据集,模型输入为.bag文件,一般位于JRDB/(train OR test)/rosbag/SEQUENCE_NAME.bag,同时需要时间戳文件,一般位于JRDB/(train OR test)/timestamps/SEQUENCE_NAME/frames_pc_im_laser.json。测试用bag文件和json文件的序列名称SEQUENCE_NAME是一一对应的。
|
||||
|
||||
首先编辑LaserDet/dr_spaam_ros/src/dr_spaam_ros/node.py主程序中的
|
||||
>```python
|
||||
>if __name__ == '__main__':
|
||||
> # init ros node here
|
||||
> rospy.init_node("dr_spaam_ros")
|
||||
> mode = 1 # 1: eval , 2: render
|
||||
> seq_name = # TODO BAGFILE_NAME (.bag) and the model detection outputs will be saved under the folder named by seq_name
|
||||
> timestamps_path = # TODO $(PATH_TO_TIMESTAMP_FILE)/frames_pc_im_laser.json
|
||||
> pipe_store = # TODO $(PATH_TO_MODEL_PIPELINES)/XXX.pipeline
|
||||
> is_rviz_supported = False # TODO if you have rviz-supported env or not
|
||||
>```
|
||||
若mode为1,模型推理结果将保存在LaserDet/dr_spaam_ros/src/outputs/seq_name下,按时间戳文件中的顺序逐帧写入txt文件,当rosbag play(步骤3)正常结束后,roslaunch(步骤2)也会正常退出。同时,也可以设置is_rviz_supported为False,每一帧的可视化结果将会保存到LaserDet/dr_spaam_ros/src/bag2png下。若mode为2,则节点会一直处于等待接收sensor message的状态,rosbag play(步骤3)结束后,roslaunch(步骤2)不会自动退出,必须手动ctrl+C。
|
||||
|
||||
运行步骤如下:
|
||||
|
||||
1. 开启一个终端输入:roscore,在测试过程中第一个终端不能关闭或停止roscore。
|
||||
|
||||
2. 开启另一个终端输入:roslaunch dr_spaam_ros dr_spaam_ros.launch,启动DR-SPAAM-ROS节点,等待片刻,直至推理模型初始化完毕,即终端显示stream创建成功。
|
||||
```
|
||||
I20221105 11:21:15.085721 29942 MxStreamManager.cpp:175] Creates streams successfully.
|
||||
I20221105 11:21:15.085903 30016 MxsmStream.cpp:326] state changed: NULL->READY
|
||||
-----------------Create Stream Successfully, ret=0-----------------
|
||||
I20221105 11:21:15.086086 30016 MxsmStream.cpp:326] state changed: READY->PAUSED
|
||||
I20221105 11:21:15.086273 30016 MxsmStream.cpp:326] state changed: PAUSED->PLAYING
|
||||
loop TOTAL_NUM_OF_FRAMES_IN_A_BAG_FILE_TO_BE_READ
|
||||
```
|
||||
|
||||
3. 开启第三个终端输入:rosbag play -r 0.015 BAG_FILE,DR-SPAAM-ROS节点开始接收每一帧信息。其中,-r是play rate,为避免丢帧造成模型推理无法正常进行,我们不得不适当降低rosbag play的速率至0.015-0.020这个范围。
|
||||
|
||||
终端显示
|
||||
```
|
||||
[ INFO] [1667556035.108439173]: Opening xxx.bag
|
||||
|
||||
Waiting 0.2 seconds after advertising topics... done.
|
||||
|
||||
Hit space to toggle paused, or 's' to step.
|
||||
[RUNNING] Bag Time: xxx Duration: xxx / xxx xxx
|
||||
Done.
|
||||
```
|
||||
直至bag文件播放结束。若rosbag play执行结束后,roslaunch的节点没有正常输出以下指示并正常退出,可能是因为速率过高造成的丢帧,不同于C++下的ROS,rospy.spin()的使用会使节点一直处于等待接收信息的状态,只能在第二个开启的终端中执行ctrl+C退出roslaunch或rosrun,
|
||||
```
|
||||
Mission completed, please check your output dir and welcome for the next use.
|
||||
```
|
||||
optional:
|
||||
|
||||
4. 开启第四个终端输入:
|
||||
```
|
||||
$ cd $(PATH_TO_LaserDet)/dr_spaam_ros
|
||||
$ source devel/setup.bash
|
||||
$ mkdir bagfiles
|
||||
$ cd bagfiles
|
||||
$ rosbag record -a
|
||||
// OR ALTERNATIVE
|
||||
$ rosbag record -O subset /segway/scan_multi /dr_spaam_rviz /dr_spaam_detections
|
||||
```
|
||||
其中-a表示把rosrun发表的所有topics都保存到新建的.bag文件中。这个方法不需要提前执行rostopic list -v查看所有topics,且后期更换任意一支持平台可视化时更方便,只需执行rosrun rviz rviz -d example.rziz,启动GUI界面。注意该选项要求开发板预留足够的free space(至少大于当前bag文件+1GB)。注意,若选择用rosbag保存subset,后两个topics即{/dr_spaam_rviz, /dr_spaam_detections}是在节点启动后才会发布的。
|
||||
```
|
||||
$:rostopic hz /segway/scan_multi # SensorMessage input of node dr_spaam_ros
|
||||
$:rostopic hz /dr_spaam_rviz # Published topic of node dr_spaam_ros
|
||||
$:rostopic hz /dr_spaam_detections # Published topic of node dr_spaam_ros
|
||||
```
|
||||
|
||||
### 8.3 ROS精度测试
|
||||
|
||||
本项目提供精度测试代码,位于LaserDet/scripts/eval_external_ros.py,使用方法与LaserDet/scripts/eval_external.py相同,此处不作过多展开。
|
||||
|
||||
## 9 常见问题
|
||||
|
||||
### 9.1 测试输入用例不存在
|
||||
|
||||
解决方案:检查输入路径。
|
||||
|
||||
### 9.2 测试输入格式错误
|
||||
|
||||
解决方案:严格按照数据集处理流程处理测试数据。
|
||||
|
||||
### 9.3 测试数据不符合模型输入
|
||||
|
||||
如果采用本说明提供的数据集以外的数据作为测试用例,可能需要自行实现前处理。
|
||||
|
||||
## 10 参考文献
|
||||
```BibTeX
|
||||
@article{Jia2021Person2DRange,
|
||||
title = {{Self-Supervised Person Detection in 2D Range Data using a
|
||||
Calibrated Camera}},
|
||||
author = {Dan Jia and Mats Steinweg and Alexander Hermans and Bastian Leibe},
|
||||
booktitle = {International Conference on Robotics and Automation (ICRA)},
|
||||
year = {2021}
|
||||
}
|
||||
|
||||
@inproceedings{Jia2020DRSPAAM,
|
||||
title = {{DR-SPAAM: A Spatial-Attention and Auto-regressive
|
||||
Model for Person Detection in 2D Range Data}},
|
||||
author = {Dan Jia and Alexander Hermans and Bastian Leibe},
|
||||
booktitle = {International Conference on Intelligent Robots and Systems (IROS)},
|
||||
year = {2020}
|
||||
}
|
||||
```
|
28
2D_LiDAR_Pedestrain_Detection/lidar_quicktest.sh
Normal file
28
2D_LiDAR_Pedestrain_Detection/lidar_quicktest.sh
Normal file
@@ -0,0 +1,28 @@
|
||||
# Copyright(C) 2021. Huawei Technologies Co.,Ltd. All rights reserved.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
# load envs
|
||||
# source ./envs/env.sh
|
||||
|
||||
|
||||
export MX_SDK_HOME="/home/HwHiAiUser/mindx_sdk/mxVision"
|
||||
export LD_LIBRARY_PATH=${MX_SDK_HOME}/lib:${MX_SDK_HOME}/opensource/lib:/usr/local/Ascend/ascend-toolkit/latest/acllib/lib64:/usr/local/Ascend/driver/lib64/
|
||||
export GST_PLUGIN_SCANNER=${MX_SDK_HOME}/opensource/libexec/gstreamer-1.0/gst-plugin-scanner
|
||||
export GST_PLUGIN_PATH=${MX_SDK_HOME}/opensource/lib/gstreamer-1.0:${MX_SDK_HOME}/lib/plugins
|
||||
export PYTHONPATH=${MX_SDK_HOME}/python
|
||||
|
||||
export PYTHONPATH=$PYTHONPATH:./LaserDet
|
||||
|
||||
# running inference process
|
||||
nohup python -u release_lidar_speedtest.py --data_path $1 --pipe_store $2 --split $3 >> rounding_error.log 2>&1 &
|
22
2D_LiDAR_Pedestrain_Detection/lidar_submit.sh
Normal file
22
2D_LiDAR_Pedestrain_Detection/lidar_submit.sh
Normal file
@@ -0,0 +1,22 @@
|
||||
# Copyright(C) 2021. Huawei Technologies Co.,Ltd. All rights reserved.
|
||||
#
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
#
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
#
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
# load envs
|
||||
# source ./envs/env.sh
|
||||
|
||||
|
||||
export PYTHONPATH=$PYTHONPATH:./LaserDet
|
||||
|
||||
# running inference process
|
||||
python -u release_lidar_main.py --data_path $1 --pipe_store $2 --split $3 --visu $4
|
@@ -0,0 +1,25 @@
|
||||
{
|
||||
"detection0": {
|
||||
"stream_config": {
|
||||
"deviceId": "0"
|
||||
},
|
||||
"appsrc0": {
|
||||
"factory": "appsrc",
|
||||
"next": "mxpi_tensorinfer0"
|
||||
},
|
||||
"mxpi_tensorinfer0": {
|
||||
"props": {
|
||||
"dataSource": "appsrc0",
|
||||
"modelPath": "./pipelines/dr_spaam_drow_e40.om"
|
||||
},
|
||||
"factory": "mxpi_tensorinfer",
|
||||
"next": "appsink0"
|
||||
},
|
||||
"appsink0": {
|
||||
"props": {
|
||||
"blocksize": "4096000"
|
||||
},
|
||||
"factory": "appsink"
|
||||
}
|
||||
}
|
||||
}
|
@@ -0,0 +1,25 @@
|
||||
{
|
||||
"detection0": {
|
||||
"stream_config": {
|
||||
"deviceId": "0"
|
||||
},
|
||||
"appsrc0": {
|
||||
"factory": "appsrc",
|
||||
"next": "mxpi_tensorinfer0"
|
||||
},
|
||||
"mxpi_tensorinfer0": {
|
||||
"props": {
|
||||
"dataSource": "appsrc0",
|
||||
"modelPath": "/home/HwHiAiUser/edge_dev/2D_LiDAR_Pedestrain_Detection/pipelines/dr_spaam_jrdb_e20.om"
|
||||
},
|
||||
"factory": "mxpi_tensorinfer",
|
||||
"next": "appsink0"
|
||||
},
|
||||
"appsink0": {
|
||||
"props": {
|
||||
"blocksize": "4096000"
|
||||
},
|
||||
"factory": "appsink"
|
||||
}
|
||||
}
|
||||
}
|
@@ -0,0 +1,25 @@
|
||||
{
|
||||
"detection0": {
|
||||
"stream_config": {
|
||||
"deviceId": "0"
|
||||
},
|
||||
"appsrc0": {
|
||||
"factory": "appsrc",
|
||||
"next": "mxpi_tensorinfer0"
|
||||
},
|
||||
"mxpi_tensorinfer0": {
|
||||
"props": {
|
||||
"dataSource": "appsrc0",
|
||||
"modelPath": "./pipelines/drow3_drow_e40.om"
|
||||
},
|
||||
"factory": "mxpi_tensorinfer",
|
||||
"next": "appsink0"
|
||||
},
|
||||
"appsink0": {
|
||||
"props": {
|
||||
"blocksize": "4096000"
|
||||
},
|
||||
"factory": "appsink"
|
||||
}
|
||||
}
|
||||
}
|
@@ -0,0 +1,25 @@
|
||||
{
|
||||
"detection0": {
|
||||
"stream_config": {
|
||||
"deviceId": "0"
|
||||
},
|
||||
"appsrc0": {
|
||||
"factory": "appsrc",
|
||||
"next": "mxpi_tensorinfer0"
|
||||
},
|
||||
"mxpi_tensorinfer0": {
|
||||
"props": {
|
||||
"dataSource": "appsrc0",
|
||||
"modelPath": "/home/HwHiAiUser/edge_dev/2D_LiDAR_Pedestrain_Detection/pipelines/drow3_jrdb_e40.om"
|
||||
},
|
||||
"factory": "mxpi_tensorinfer",
|
||||
"next": "appsink0"
|
||||
},
|
||||
"appsink0": {
|
||||
"props": {
|
||||
"blocksize": "4096000"
|
||||
},
|
||||
"factory": "appsink"
|
||||
}
|
||||
}
|
||||
}
|
740
2D_LiDAR_Pedestrain_Detection/release_lidar_main.py
Normal file
740
2D_LiDAR_Pedestrain_Detection/release_lidar_main.py
Normal file
@@ -0,0 +1,740 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
import sys
|
||||
import os
|
||||
import stat
|
||||
|
||||
import argparse
|
||||
import numpy as np
|
||||
import matplotlib.pyplot as plt
|
||||
from matplotlib.gridspec import GridSpec
|
||||
|
||||
from StreamManagerApi import StreamManagerApi, MxDataInput, MxBufferInput, StringVector
|
||||
from StreamManagerApi import InProtobufVector, MxProtobufIn
|
||||
import MxpiDataType_pb2 as MxpiDataType
|
||||
|
||||
from srcs.data_loader import get_dataloader, drow_dataset, jrdb_dataset
|
||||
import srcs.utils.precision_recall as pru
|
||||
import srcs.utils.utils as u
|
||||
|
||||
|
||||
FLAGS = os.O_WRONLY | os.O_CREAT
|
||||
MODES = stat.S_IWUSR | stat.S_IRUSR
|
||||
|
||||
|
||||
def throw_err(data_path, data_type, split, seq_name, data_index, pipe_path):
|
||||
""" check input errors
|
||||
"""
|
||||
try:
|
||||
print("Input Check...")
|
||||
dataloader_len = {}
|
||||
if data_path:
|
||||
print(data_path, "1 +++---")
|
||||
if os.path.exists(data_path) is False:
|
||||
raise Exception("Invalid dataset path.")
|
||||
elif os.path.basename(data_path) not in ["DROWv2", "JRDB"]:
|
||||
raise Exception(
|
||||
"Unsupport Dataset. Help Info: DROWv2 OR JRDB.")
|
||||
if seq_name:
|
||||
print(seq_name, "2 +++---")
|
||||
if os.path.basename(data_path) == "DROWv2":
|
||||
seq_path = os.path.join(
|
||||
data_path, split.split("_")[0], seq_name)
|
||||
else:
|
||||
|
||||
seq_path = os.path.join(
|
||||
data_path, "{}_dataset".format(
|
||||
split.split("_")[0]), "lasers", seq_name)
|
||||
if os.path.exists(seq_path) is False:
|
||||
raise Exception("Invalid sequence path: {}.".format(seq_path))
|
||||
if data_type:
|
||||
print(data_type, "3 +++---")
|
||||
if os.path.basename(data_path) == "DROWv2":
|
||||
[(root, dirs, files)] = os.walk(
|
||||
os.path.join(data_path, split.split("_")[0]))
|
||||
cur_data_type = [file_name for file_name in files if os.path.splitext(
|
||||
file_name)[-1] == '.csv']
|
||||
for idx, name in enumerate(cur_data_type):
|
||||
seq_wc = []
|
||||
basename = os.path.basename(name)
|
||||
with open(os.path.join(root, name.replace("csv", "wc"))) as f:
|
||||
for line in f:
|
||||
seq, _ = line.split(",", 1)
|
||||
seq_wc.append(int(seq))
|
||||
dataloader_len[basename] = len(seq_wc)
|
||||
elif os.path.basename(data_path) == "JRDB":
|
||||
laser_path = os.path.join(
|
||||
data_path, "{}_dataset".format(
|
||||
split.split("_")[0]), "lasers")
|
||||
fuse_path = os.walk(laser_path)
|
||||
fuse_path = list(fuse_path)[1:]
|
||||
file_names = [fuse_path[i][-1] for i in range(len(fuse_path))]
|
||||
subpath_names = [
|
||||
os.path.basename(
|
||||
fuse_path[i][0]) for i in range(
|
||||
len(fuse_path))]
|
||||
file_names_sqz = []
|
||||
for s in file_names:
|
||||
file_names_sqz.extend(s)
|
||||
cur_data_type = [laser_name for laser_name in file_names_sqz if os.path.splitext(
|
||||
laser_name)[-1] == '.txt']
|
||||
for idx, (file_name, subpath_name) in enumerate(
|
||||
zip(file_names, subpath_names)):
|
||||
dataloader_len[subpath_name] = len(file_name)
|
||||
if len(cur_data_type) == 0:
|
||||
raise Exception(
|
||||
"Invalid DataType. Help Info: test set must contain REAL files.")
|
||||
if data_index:
|
||||
print(data_index, dataloader_len.get(seq_name, "abc"), "4 +++---")
|
||||
if data_index > dataloader_len.get(seq_name, "abc") - 1 or data_index < 0:
|
||||
raise Exception(
|
||||
"Invalid frame id. Help Info: The length of dataloader is {}.".format(
|
||||
dataloader_len.get(seq_name, "abc")))
|
||||
if pipe_path:
|
||||
print(pipe_path, "5 +++---")
|
||||
if os.path.exists(pipe_path) is False:
|
||||
raise Exception(
|
||||
"Invalid .pipeline path. Help Info: please check your .pipeline path.")
|
||||
else:
|
||||
with open(pipe_path, 'rb') as f:
|
||||
pipe_b = f.read()
|
||||
pipe_str = str(pipe_b, encoding='utf-8')
|
||||
pipe_dic = eval(pipe_str)
|
||||
if os.path.exists(
|
||||
pipe_dic['detection0']['mxpi_tensorinfer0']['props']['modelPath']) is False:
|
||||
raise Exception(
|
||||
"Invalid .om path. Help Info: please modify .om path in .pipeline.")
|
||||
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
|
||||
|
||||
def sigmoid(z):
|
||||
return 1.0 / (1.0 + np.exp(-z))
|
||||
|
||||
|
||||
def cross_entropy_with_logits(x, y):
|
||||
return -np.sum(x * np.log(y + 1e-7))
|
||||
|
||||
|
||||
def rooted_mean_squared_error(x, y):
|
||||
mse = 0.5 * np.sum((y - x)**2)
|
||||
return np.sqrt(np.sum(mse)) / len(y)
|
||||
|
||||
|
||||
def save_detections(det_coords, det_scores, occluded):
|
||||
|
||||
if det_scores is None:
|
||||
det_scores = np.ones(len(det_coords), dtype=np.float32)
|
||||
|
||||
if occluded is None:
|
||||
occluded = np.zeros(len(det_coords), dtype=np.int32)
|
||||
|
||||
long_str = ""
|
||||
for cls, xy, occ in zip(det_scores, det_coords, occluded):
|
||||
long_str += f"Pedestrian 0 {occ} 0 0 0 0 0 0 0 0 0 {xy[0]} {xy[1]} 0 0 {cls}\n"
|
||||
long_str = long_str.strip("\n")
|
||||
|
||||
return long_str
|
||||
|
||||
|
||||
def rphi_xy_convertor(rdius, ang):
|
||||
return rdius * np.cos(ang), rdius * np.sin(ang)
|
||||
|
||||
|
||||
def can_glob_convertor(rdius, ang, dx, dy):
|
||||
tmp_y = rdius + dy
|
||||
tmp_phi = np.arctan2(dx, tmp_y)
|
||||
dets_phi = tmp_phi + ang
|
||||
dets_r = tmp_y / np.cos(tmp_phi)
|
||||
return dets_r, dets_phi
|
||||
|
||||
|
||||
def plot_one_frame_beta(
|
||||
batch_dict,
|
||||
frame_idx,
|
||||
pred_cls=None,
|
||||
pred_reg=None,
|
||||
xlim=(-7, 7),
|
||||
ylim=(-7, 7),
|
||||
):
|
||||
fig_handle = plt.figure(figsize=(10, 10))
|
||||
ax_handle = fig_handle.add_subplot(111)
|
||||
|
||||
ax_handle.set_xlim(xlim[0], xlim[1])
|
||||
ax_handle.set_ylim(ylim[0], ylim[1])
|
||||
ax_handle.set_xlabel("x [m]")
|
||||
ax_handle.set_ylabel("y [m]")
|
||||
ax_handle.set_aspect("equal")
|
||||
ax_handle.set_title(f"{frame_idx}")
|
||||
|
||||
# scan and cls label
|
||||
scan_r = batch_dict["scans"][-1]
|
||||
scan_phi = batch_dict["scan_phi"]
|
||||
|
||||
# plot scan
|
||||
scan_x, scan_y = rphi_xy_convertor(scan_r, scan_phi)
|
||||
ax_handle.scatter(scan_x, scan_y, s=1, c="black")
|
||||
pred_r, pred_phi = can_glob_convertor(
|
||||
scan_r, scan_phi, pred_reg[:, 0], pred_reg[:, 1]
|
||||
)
|
||||
pred_x, pred_y = rphi_xy_convertor(pred_r, pred_phi)
|
||||
ax_handle.scatter(pred_x, pred_y, s=2, c="red")
|
||||
|
||||
return fig_handle, ax_handle
|
||||
|
||||
|
||||
def plot_one_frame(
|
||||
batch_dict,
|
||||
frame_idx,
|
||||
pred_cls=None,
|
||||
pred_reg=None,
|
||||
dets_cls=None,
|
||||
dets_xy=None,
|
||||
xlim=(-7, 7),
|
||||
ylim=(-7, 7),
|
||||
):
|
||||
|
||||
fig_handle = plt.figure(figsize=(10, 10))
|
||||
ax_handle = fig_handle.add_subplot(111)
|
||||
|
||||
ax_handle.set_xlim(xlim[0], xlim[1])
|
||||
ax_handle.set_ylim(ylim[0], ylim[1])
|
||||
ax_handle.set_xlabel("x [m]")
|
||||
ax_handle.set_ylabel("y [m]")
|
||||
ax_handle.set_aspect("equal")
|
||||
ax_handle.set_title(f"{frame_idx}")
|
||||
|
||||
# scan and cls label
|
||||
scan_r = batch_dict["scans"][frame_idx][-1] if frame_idx is not None else batch_dict["scans"][-1]
|
||||
scan_phi = batch_dict["scan_phi"][frame_idx] if frame_idx is not None else batch_dict["scan_phi"]
|
||||
target_cls = batch_dict["target_cls"][frame_idx] if frame_idx is not None else batch_dict["target_cls"]
|
||||
|
||||
# plot scan
|
||||
scan_x, scan_y = rphi_xy_convertor(scan_r, scan_phi)
|
||||
ax_handle.scatter(scan_x[target_cls < 0],
|
||||
scan_y[target_cls < 0], s=1, c="orange")
|
||||
ax_handle.scatter(scan_x[target_cls == 0],
|
||||
scan_y[target_cls == 0], s=1, c="black")
|
||||
ax_handle.scatter(scan_x[target_cls > 0],
|
||||
scan_y[target_cls > 0], s=1, c="green")
|
||||
|
||||
# annotation
|
||||
if frame_idx is not None:
|
||||
ann = batch_dict["dets_wp"][frame_idx]
|
||||
ann_valid_mask = batch_dict["anns_valid_mask"][frame_idx]
|
||||
else:
|
||||
ann = batch_dict["dets_wp"]
|
||||
ann_valid_mask = batch_dict["anns_valid_mask"]
|
||||
if len(ann) > 0:
|
||||
ann = np.array(ann)
|
||||
det_x, det_y = rphi_xy_convertor(ann[:, 0], ann[:, 1])
|
||||
for x, y, valid in zip(det_x, det_y, ann_valid_mask):
|
||||
c = "blue" if valid else "orange"
|
||||
c = plt.Circle((x, y), radius=0.4, color=c, fill=False)
|
||||
ax_handle.add_artist(c)
|
||||
|
||||
# regression target
|
||||
target_reg = batch_dict["target_reg"][frame_idx] if frame_idx is not None else batch_dict["target_reg"]
|
||||
dets_r, dets_phi = can_glob_convertor(
|
||||
scan_r, scan_phi, target_reg[:, 0], target_reg[:, 1]
|
||||
)
|
||||
dets_r = dets_r[target_cls > 0]
|
||||
dets_phi = dets_phi[target_cls > 0]
|
||||
dets_x, dets_y = rphi_xy_convertor(dets_r, dets_phi)
|
||||
ax_handle.scatter(dets_x, dets_y, s=10, c="blue")
|
||||
|
||||
# regression result
|
||||
if dets_xy is not None and dets_cls is not None:
|
||||
ax_handle.scatter(dets_xy[:, 0], dets_xy[:, 1],
|
||||
marker="x", s=40, c="black")
|
||||
|
||||
if pred_cls is not None and pred_reg is not None:
|
||||
pred_r, pred_phi = can_glob_convertor(
|
||||
scan_r, scan_phi, pred_reg[:, 0], pred_reg[:, 1]
|
||||
)
|
||||
pred_x, pred_y = rphi_xy_convertor(pred_r, pred_phi)
|
||||
ax_handle.scatter(pred_x, pred_y, s=2, c="red")
|
||||
|
||||
return fig_handle, ax_handle
|
||||
|
||||
|
||||
def nms_predicted_center(
|
||||
scan_grid, phi_grid, pred_cls, pred_reg, min_dist=0.5
|
||||
):
|
||||
assert len(pred_cls.shape) == 1
|
||||
|
||||
pred_r, pred_phi = can_glob_convertor(
|
||||
scan_grid, phi_grid, pred_reg[:, 0], pred_reg[:, 1]
|
||||
)
|
||||
pred_xs, pred_ys = rphi_xy_convertor(pred_r, pred_phi)
|
||||
|
||||
# sort prediction with descending confidence
|
||||
sort_inds = np.argsort(pred_cls)[::-1]
|
||||
|
||||
pred_xs, pred_ys = pred_xs[sort_inds], pred_ys[sort_inds]
|
||||
pred_cls = pred_cls[sort_inds]
|
||||
|
||||
# compute pair-wise distance
|
||||
num_pts = len(scan_grid)
|
||||
xdiff = pred_xs.reshape(num_pts, 1) - pred_xs.reshape(1, num_pts)
|
||||
ydiff = pred_ys.reshape(num_pts, 1) - pred_ys.reshape(1, num_pts)
|
||||
p_dist = np.sqrt(np.square(xdiff) + np.square(ydiff))
|
||||
|
||||
# nms
|
||||
keep = np.ones(num_pts, dtype=np.bool_)
|
||||
instance_mask = np.zeros(num_pts, dtype=np.int32)
|
||||
instance_id = 1
|
||||
for i in range(num_pts):
|
||||
if not keep[i]:
|
||||
continue
|
||||
|
||||
dup_inds = p_dist[i] < min_dist
|
||||
keep[dup_inds] = False
|
||||
keep[i] = True
|
||||
instance_mask[sort_inds[dup_inds]] = instance_id
|
||||
instance_id += 1
|
||||
|
||||
det_xys = np.stack((pred_xs, pred_ys), axis=1)[keep]
|
||||
det_cls = pred_cls[keep]
|
||||
|
||||
return det_xys, det_cls, instance_mask
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description="arg parser")
|
||||
parser.add_argument("--data_path",
|
||||
type=str,
|
||||
required=True,
|
||||
help="dataset directory.")
|
||||
parser.add_argument("--pipe_store",
|
||||
type=str,
|
||||
required=True,
|
||||
help="collecting pipeline.")
|
||||
parser.add_argument("--split",
|
||||
type=str,
|
||||
required=True,
|
||||
help="test, test_nano, or val.")
|
||||
parser.add_argument("--visu",
|
||||
type=bool,
|
||||
required=True,
|
||||
help="visulizing the detection results.")
|
||||
parser.add_argument("--seq_name",
|
||||
type=str,
|
||||
default=None,
|
||||
help="sequence name for quick test.")
|
||||
parser.add_argument("--frame_id",
|
||||
type=int,
|
||||
default=None,
|
||||
help="frame index for quick test.")
|
||||
args = parser.parse_args()
|
||||
|
||||
# input check (data_path, data_type, split, seq_name, data_index,
|
||||
# pipe_path)
|
||||
throw_err(args.data_path,
|
||||
True,
|
||||
args.split,
|
||||
args.seq_name,
|
||||
args.frame_id,
|
||||
args.pipe_store)
|
||||
|
||||
dataset_name = os.path.basename(args.data_path)
|
||||
model_name = os.path.basename(args.pipe_store).split('.')[
|
||||
0].split('_')[0].upper()
|
||||
|
||||
unseen_frame = False
|
||||
if args.frame_id:
|
||||
if "DROW" in args.data_path:
|
||||
test_dataset = drow_dataset.DROWDataset(
|
||||
split=args.split,
|
||||
data_dir=[args.data_path, args.seq_name],
|
||||
scan_type=model_name)
|
||||
test_loader = [test_dataset.__getitem__(int(args.frame_id))]
|
||||
try:
|
||||
if len(test_loader) == 0:
|
||||
raise Exception(
|
||||
"Sorry we cannot visit this frame at this time.")
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
if "JRDB" in args.data_path:
|
||||
test_dataset = jrdb_dataset.JRDBDataset(
|
||||
split=args.split,
|
||||
jrdb_split=args.seq_name,
|
||||
data_dir_cfg=args.data_path,
|
||||
scan_type=model_name)
|
||||
frame_url = str(args.frame_id).zfill(6) + ".txt"
|
||||
test_loader = list(
|
||||
filter(
|
||||
lambda test_sample: os.path.basename(
|
||||
test_sample["laser_frame"]["url"].replace(
|
||||
"\\",
|
||||
"/")) == frame_url,
|
||||
test_dataset))
|
||||
print("len of test_loader", len(test_loader))
|
||||
if len(test_loader) == 0:
|
||||
unseen_frame = True
|
||||
num_scans = 1 if model_name == "DROW" else 10
|
||||
scan_url = os.path.join(args.data_path,
|
||||
args.split.split("_")[0] + "_dataset",
|
||||
"lasers",
|
||||
args.seq_name,
|
||||
frame_url)
|
||||
current_frame_idx = int(
|
||||
os.path.basename(scan_url).split(".")[0])
|
||||
frames_list = []
|
||||
for del_idx in range(num_scans, 0, -1):
|
||||
frame_idx = max(0, current_frame_idx - del_idx * 1)
|
||||
laser_url = os.path.join(
|
||||
os.path.dirname(scan_url),
|
||||
str(frame_idx).zfill(6) +
|
||||
".txt").replace(
|
||||
"\\",
|
||||
"/")
|
||||
laser_loaded = np.loadtxt(
|
||||
os.path.join(
|
||||
args.data_path,
|
||||
laser_url),
|
||||
dtype=np.float32)
|
||||
frames_list.append(laser_loaded)
|
||||
|
||||
batch_dict = {}
|
||||
laser_data = np.stack(frames_list, axis=0)
|
||||
|
||||
laser_grid = np.linspace(-np.pi, np.pi,
|
||||
laser_data.shape[1], dtype=np.float32)
|
||||
ct_kwargs = {
|
||||
"win_width": 1.0,
|
||||
"win_depth": 0.5,
|
||||
"num_ct_pts": 56,
|
||||
"pad_val": 29.99,
|
||||
}
|
||||
batch_dict["scans"] = laser_data
|
||||
batch_dict["scan_phi"] = laser_grid
|
||||
batch_dict["input"] = u.trim_the_scans(
|
||||
laser_data, laser_grid, stride=1, **ct_kwargs,)
|
||||
test_loader.append(batch_dict)
|
||||
|
||||
elif args.seq_name:
|
||||
test_loader = get_dataloader(
|
||||
split=args.split,
|
||||
batch_size=1,
|
||||
num_workers=1, # avoid TypeError: Caught TypeError in DataLoader worker process 0
|
||||
shuffle=False,
|
||||
dataset_pth=[args.data_path, args.seq_name],
|
||||
scan_type=model_name,
|
||||
)
|
||||
else:
|
||||
test_loader = get_dataloader(
|
||||
split=args.split, # "val", "test", "test_nano"
|
||||
batch_size=1,
|
||||
num_workers=1, # avoid TypeError: Caught TypeError in DataLoader worker process 0
|
||||
shuffle=False,
|
||||
dataset_pth=args.data_path,
|
||||
scan_type=model_name,
|
||||
)
|
||||
|
||||
# The following belongs to the SDK Process
|
||||
stream_manager_api = StreamManagerApi()
|
||||
# init stream manager
|
||||
ret = stream_manager_api.InitManager()
|
||||
if ret != 0:
|
||||
print("Failed to init Stream manager, ret=%s" % str(ret))
|
||||
exit()
|
||||
else:
|
||||
print("-----------------创建流管理StreamManager并初始化-----------------")
|
||||
|
||||
# create streams by pipeline config file
|
||||
with open(args.pipe_store, 'rb') as f:
|
||||
print("-----------------正在读取读取pipeline-----------------")
|
||||
pipeline_str = f.read()
|
||||
print("-----------------成功读取pipeline-----------------")
|
||||
|
||||
ret = stream_manager_api.CreateMultipleStreams(pipeline_str)
|
||||
|
||||
# Print error message
|
||||
if ret != 0:
|
||||
print(
|
||||
"-----------------Failed to create Stream, ret=%s-----------------" %
|
||||
str(ret))
|
||||
else:
|
||||
print(
|
||||
"-----------------Create Stream Successfully, ret=%s-----------------" %
|
||||
str(ret))
|
||||
# Stream name
|
||||
|
||||
stream_name = b'detection0'
|
||||
|
||||
in_plugin_id = 0
|
||||
tb_dict_list = []
|
||||
dets_xy_accum = {}
|
||||
dets_cls_accum = {}
|
||||
dets_inds_accum = {}
|
||||
gts_xy_accum = {}
|
||||
gts_inds_accum = {}
|
||||
fig_dict = {}
|
||||
|
||||
for count, batch_dict in enumerate(test_loader):
|
||||
if count >= 1e9:
|
||||
break
|
||||
tensor_package_list = MxpiDataType.MxpiTensorPackageList()
|
||||
tensor_package = tensor_package_list.tensorPackageVec.add()
|
||||
tsor = batch_dict.get("input", "abc").astype('<f4')
|
||||
if args.frame_id:
|
||||
tsor = np.expand_dims(tsor, axis=0)
|
||||
try:
|
||||
if tsor.shape[1] != 450 and tsor.shape[1] != 1091:
|
||||
raise AssertionError(
|
||||
"InputTensor shape does not match model inputTensors.")
|
||||
except AssertionError as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
array_bytes = tsor.tobytes()
|
||||
data_input = MxDataInput()
|
||||
data_input.data = array_bytes
|
||||
tensor_vec = tensor_package.tensorVec.add()
|
||||
tensor_vec.deviceId = 0
|
||||
tensor_vec.memType = 0
|
||||
for i in tsor.shape:
|
||||
tensor_vec.tensorShape.append(i)
|
||||
tensor_vec.dataStr = data_input.data
|
||||
tensor_vec.tensorDataSize = len(array_bytes)
|
||||
|
||||
key = "appsrc{}".format(in_plugin_id).encode('utf-8')
|
||||
protobuf_vec = InProtobufVector()
|
||||
protobuf = MxProtobufIn()
|
||||
protobuf.key = key
|
||||
protobuf.type = b'MxTools.MxpiTensorPackageList'
|
||||
protobuf.protobuf = tensor_package_list.SerializeToString()
|
||||
protobuf_vec.push_back(protobuf)
|
||||
|
||||
ret = stream_manager_api.SendProtobuf(
|
||||
stream_name, in_plugin_id, protobuf_vec)
|
||||
# in_plugin_id currently fixed to 0 indicating the input port number
|
||||
if ret != 0:
|
||||
print("Failed to send data to stream.")
|
||||
exit()
|
||||
|
||||
key_vec = StringVector()
|
||||
key_vec.push_back(b'mxpi_tensorinfer0')
|
||||
infer_result = stream_manager_api.GetProtobuf(stream_name, 0, key_vec)
|
||||
|
||||
if infer_result.size() == 0:
|
||||
print("infer_result is null")
|
||||
exit()
|
||||
if infer_result[0].errorCode != 0:
|
||||
print("GetProtobuf error. errorCode=%d" % (
|
||||
infer_result[0].errorCode))
|
||||
exit()
|
||||
result = MxpiDataType.MxpiTensorPackageList()
|
||||
result.ParseFromString(infer_result[0].messageBuf)
|
||||
pred_cls = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[0].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[0].tensorShape))
|
||||
pred_reg = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[1].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[1].tensorShape))
|
||||
prediction_shape = result.tensorPackageVec[0].tensorVec[1].tensorShape
|
||||
|
||||
print("Launching eval...")
|
||||
batch_size = len(batch_dict.get("scans", "abc"))
|
||||
if unseen_frame:
|
||||
print("Skip eval...")
|
||||
fig, ax = plot_one_frame_beta(
|
||||
batch_dict, args.frame_id, pred_cls[0], pred_reg[0])
|
||||
fig_name = f"figs_wo_anno/{args.seq_name}/{str(args.frame_id).zfill(6)}.png"
|
||||
fig_save_dir = os.getcwd()
|
||||
fig_file = os.path.join(fig_save_dir, fig_name)
|
||||
os.makedirs(os.path.dirname(fig_file), exist_ok=True)
|
||||
fig.savefig(fig_file)
|
||||
plt.close(fig)
|
||||
break
|
||||
for ib in range(batch_size):
|
||||
if args.frame_id:
|
||||
scan = batch_dict.get("scans", "abc")
|
||||
scan_phi = batch_dict.get("scan_phi", "abc")
|
||||
tar_cls = batch_dict.get("target_cls", "abc")
|
||||
tar_reg = batch_dict.get("target_reg", "abc")
|
||||
pred_cls_sigmoid = sigmoid(pred_cls.squeeze())
|
||||
det_xy, det_cls, _ = nms_predicted_center(
|
||||
scan[-1], scan_phi, pred_cls_sigmoid, pred_reg.squeeze())
|
||||
frame_id = batch_dict.get("frame_id", "abc")
|
||||
frame_id = f"{frame_id:06d}"
|
||||
sequence = batch_dict.get("sequence", "abc")
|
||||
# save det_xy, det_cls for evaluation
|
||||
anns_rphi = batch_dict.get("dets_wp", "abc")
|
||||
if len(anns_rphi) > 0:
|
||||
anns_rphi = np.array(anns_rphi, dtype=np.float32)
|
||||
gts_xy = np.stack(rphi_xy_convertor(
|
||||
anns_rphi[:, 0], anns_rphi[:, 1]), axis=1)
|
||||
gts_occluded = np.logical_not(
|
||||
batch_dict.get("anns_valid_mask", "abc")).astype(
|
||||
np.int32)
|
||||
else:
|
||||
gts_xy = ""
|
||||
else:
|
||||
scan = batch_dict.get("scans", "abc")[ib]
|
||||
scan_phi = batch_dict.get("scan_phi", "abc")[ib]
|
||||
tar_cls = batch_dict.get("target_cls", "abc")[ib]
|
||||
tar_reg = batch_dict.get("target_reg", "abc")[ib]
|
||||
pred_cls_sigmoid = sigmoid(pred_cls[ib].squeeze())
|
||||
det_xy, det_cls, _ = nms_predicted_center(
|
||||
scan[-1], scan_phi, pred_cls_sigmoid, pred_reg[ib]) # by batch
|
||||
frame_id = batch_dict.get("frame_id", "abc")[ib]
|
||||
frame_id = f"{frame_id:06d}"
|
||||
sequence = batch_dict.get("sequence", "abc")[ib]
|
||||
# save det_xy, det_cls for evaluation
|
||||
anns_rphi = batch_dict.get("dets_wp", "abc")[ib]
|
||||
if len(anns_rphi) > 0:
|
||||
anns_rphi = np.array(anns_rphi, dtype=np.float32)
|
||||
gts_xy = np.stack(rphi_xy_convertor(
|
||||
anns_rphi[:, 0], anns_rphi[:, 1]), axis=1)
|
||||
gts_occluded = np.logical_not(
|
||||
batch_dict.get("anns_valid_mask", "abc")[ib]).astype(
|
||||
np.int32)
|
||||
else:
|
||||
gts_xy = ""
|
||||
if "JRDB" in args.data_path:
|
||||
seq_nname = args.seq_name if args.seq_name else args.split
|
||||
det_str = save_detections(
|
||||
det_xy, det_cls, None)
|
||||
det_fname = os.path.join(
|
||||
os.getcwd(),
|
||||
f"outputs_{dataset_name}_{seq_nname}_{model_name}/detections/{sequence}/{frame_id}.txt")
|
||||
os.makedirs(os.path.dirname(det_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(det_fname, FLAGS, MODES), "w") as fdo:
|
||||
fdo.write(det_str)
|
||||
gts_str = save_detections(
|
||||
gts_xy, None, gts_occluded)
|
||||
gts_fname = os.path.join(
|
||||
os.getcwd(),
|
||||
f"outputs_{dataset_name}_{seq_nname}_{model_name}/groundtruth/{sequence}/{frame_id}.txt")
|
||||
os.makedirs(os.path.dirname(gts_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(gts_fname, FLAGS, MODES), "w") as fgo:
|
||||
fgo.write(gts_str)
|
||||
|
||||
if len(det_xy) > 0: # if not empty
|
||||
try:
|
||||
if sequence not in list(dets_cls_accum.keys()):
|
||||
dets_xy_accum[sequence] = []
|
||||
dets_cls_accum[sequence] = []
|
||||
dets_inds_accum[sequence] = []
|
||||
dets_xy_accum[sequence].append(det_xy)
|
||||
dets_cls_accum[sequence].append(det_cls)
|
||||
dets_inds_accum[sequence] += [frame_id] * len(det_xy)
|
||||
except KeyError:
|
||||
print("Dict KeyError!")
|
||||
|
||||
if len(gts_xy) > 0: # if not empty
|
||||
try:
|
||||
if sequence not in list(gts_xy_accum.keys()):
|
||||
gts_xy_accum[sequence], gts_inds_accum[sequence] = [], []
|
||||
gts_xy_accum[sequence].append(gts_xy)
|
||||
gts_inds_accum[sequence] += [frame_id] * len(gts_xy)
|
||||
except KeyError:
|
||||
print("Dict KeyError!")
|
||||
|
||||
# do the following in batch
|
||||
tar_shape = np.prod(batch_dict.get("target_cls", "abc").shape)
|
||||
|
||||
tar_cls = tar_cls.reshape(tar_shape)
|
||||
pred_cls = pred_cls.reshape(tar_shape)
|
||||
|
||||
# accumulate detections in all frames
|
||||
if args.visu: # save fig
|
||||
fig_save_dir = os.getcwd()
|
||||
# fig_handle and axis_handle
|
||||
if args.frame_id:
|
||||
fig, ax = plot_one_frame(
|
||||
batch_dict, None, pred_cls[0], pred_reg[0], det_cls, det_xy)
|
||||
if args.seq_name:
|
||||
fig_name = f"figs/{args.seq_name}/{frame_id}.png"
|
||||
else:
|
||||
fig_name = f"figs/{sequence}/{frame_id}.png"
|
||||
else:
|
||||
fig, ax = plot_one_frame(
|
||||
batch_dict, ib, pred_cls[ib], pred_reg[ib], det_cls, det_xy)
|
||||
fig_name = f"figs/{sequence}/{frame_id}.png"
|
||||
fig_file = os.path.join(
|
||||
fig_save_dir, fig_name)
|
||||
os.makedirs(os.path.dirname(fig_file), exist_ok=True)
|
||||
fig.savefig(fig_file)
|
||||
plt.close(fig)
|
||||
|
||||
# evaluate
|
||||
if "DROW" in args.data_path or args.frame_id is not None:
|
||||
for key in [*dets_cls_accum]:
|
||||
dets_xy = np.concatenate(dets_xy_accum.get(key, "abc"), axis=0)
|
||||
dets_cls = np.concatenate(dets_cls_accum.get(key, "abc"))
|
||||
dets_inds = np.array(dets_inds_accum.get(key, "abc"))
|
||||
gts_xy = np.concatenate(gts_xy_accum.get(key, "abc"), axis=0)
|
||||
gts_inds = np.array(gts_inds_accum.get(key, "abc"))
|
||||
# evaluate all sequences
|
||||
|
||||
seq03, seq05 = [], []
|
||||
try:
|
||||
seq03.append(
|
||||
pru.eval_internal(
|
||||
dets_xy,
|
||||
dets_cls,
|
||||
dets_inds,
|
||||
gts_xy,
|
||||
gts_inds,
|
||||
ar=0.3))
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
try:
|
||||
seq05.append(
|
||||
pru.eval_internal(
|
||||
dets_xy,
|
||||
dets_cls,
|
||||
dets_inds,
|
||||
gts_xy,
|
||||
gts_inds,
|
||||
ar=0.5))
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
if len(seq03) > 0 and len(seq05) > 0:
|
||||
print(f"Evaluating {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq03[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq03[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq03[-1]['eer']:4f}\n"
|
||||
f"AP_0.5 {seq05[-1]['ap']:4f} "
|
||||
f"peak-F1_0.5 {seq05[-1]['peak_f1']:4f} "
|
||||
f"EER_0.5 {seq05[-1]['eer']:4f}\n"
|
||||
)
|
||||
elif len(seq03) > 0:
|
||||
print(f"Evaluating ar=0.3 {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq03[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq03[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq03[-1]['eer']:4f}\n"
|
||||
)
|
||||
elif len(seq05) > 0:
|
||||
print(f"Evaluating ar=0.5 {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq05[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq05[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq05[-1]['eer']:4f}\n"
|
||||
)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
611
2D_LiDAR_Pedestrain_Detection/release_lidar_speedtest.py
Normal file
611
2D_LiDAR_Pedestrain_Detection/release_lidar_speedtest.py
Normal file
@@ -0,0 +1,611 @@
|
||||
# Copyright 2021 Huawei Technologies Co., Ltd
|
||||
# Licensed under the Apache License, Version 2.0 (the "License");
|
||||
# you may not use this file except in compliance with the License.
|
||||
# You may obtain a copy of the License at
|
||||
|
||||
# http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
# Unless required by applicable law or agreed to in writing, software
|
||||
# distributed under the License is distributed on an "AS IS" BASIS,
|
||||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
# See the License for the specific language governing permissions and
|
||||
# limitations under the License.
|
||||
|
||||
from ast import arg
|
||||
from dis import COMPILER_FLAG_NAMES
|
||||
import json
|
||||
import sys
|
||||
import os
|
||||
import stat
|
||||
|
||||
from pickletools import int4
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
import numpy as np
|
||||
|
||||
from StreamManagerApi import StreamManagerApi, MxDataInput, MxBufferInput, StringVector
|
||||
from StreamManagerApi import InProtobufVector, MxProtobufIn
|
||||
import MxpiDataType_pb2 as MxpiDataType
|
||||
|
||||
from srcs.data_loader import get_dataloader, drow_dataset, jrdb_dataset
|
||||
import srcs.utils.precision_recall as pru
|
||||
import srcs.utils.utils as u
|
||||
|
||||
FLAGS = os.O_WRONLY | os.O_CREAT
|
||||
MODES = stat.S_IWUSR | stat.S_IRUSR
|
||||
|
||||
|
||||
def throw_err(data_path, data_type, split, seq_name, data_index, pipe_path):
|
||||
""" check input errors
|
||||
"""
|
||||
try:
|
||||
print("Input Check...")
|
||||
dataloader_len = {}
|
||||
if data_path:
|
||||
print(data_path, "1 +++---")
|
||||
if os.path.exists(data_path) is False:
|
||||
raise Exception("Invalid dataset path.")
|
||||
elif os.path.basename(data_path) not in ["DROWv2", "JRDB"]:
|
||||
raise Exception(
|
||||
"Unsupport Dataset. Help Info: DROWv2 OR JRDB.")
|
||||
if seq_name:
|
||||
print(seq_name, "2 +++---")
|
||||
if os.path.basename(data_path) == "DROWv2":
|
||||
seq_path = os.path.join(
|
||||
data_path, split.split("_")[0], seq_name)
|
||||
else:
|
||||
|
||||
seq_path = os.path.join(
|
||||
data_path, "{}_dataset".format(
|
||||
split.split("_")[0]), "lasers", seq_name)
|
||||
if os.path.exists(seq_path) is False:
|
||||
raise Exception("Invalid sequence path: {}.".format(seq_path))
|
||||
if data_type:
|
||||
print(data_type, "3 +++---")
|
||||
if os.path.basename(data_path) == "DROWv2":
|
||||
[(root, dirs, files)] = os.walk(
|
||||
os.path.join(data_path, split.split("_")[0]))
|
||||
cur_data_type = [file_name for file_name in files if os.path.splitext(
|
||||
file_name)[-1] == '.csv']
|
||||
for idx, name in enumerate(cur_data_type):
|
||||
seq_wc = []
|
||||
basename = os.path.basename(name)
|
||||
with open(os.path.join(root, name.replace("csv", "wc"))) as f:
|
||||
for line in f:
|
||||
seq, _ = line.split(",", 1)
|
||||
seq_wc.append(int(seq))
|
||||
dataloader_len[basename] = len(seq_wc)
|
||||
elif os.path.basename(data_path) == "JRDB":
|
||||
laser_path = os.path.join(
|
||||
data_path, "{}_dataset".format(
|
||||
split.split("_")[0]), "lasers")
|
||||
fuse_path = os.walk(laser_path)
|
||||
fuse_path = list(fuse_path)[1:]
|
||||
file_names = [fuse_path[i][-1] for i in range(len(fuse_path))]
|
||||
subpath_names = [
|
||||
os.path.basename(
|
||||
fuse_path[i][0]) for i in range(
|
||||
len(fuse_path))]
|
||||
file_names_sqz = []
|
||||
for s in file_names:
|
||||
file_names_sqz.extend(s)
|
||||
cur_data_type = [laser_name for laser_name in file_names_sqz if os.path.splitext(
|
||||
laser_name)[-1] == '.txt']
|
||||
for idx, (file_name, subpath_name) in enumerate(
|
||||
zip(file_names, subpath_names)):
|
||||
dataloader_len[subpath_name] = len(file_name)
|
||||
if len(cur_data_type) == 0:
|
||||
raise Exception(
|
||||
"Invalid DataType. Help Info: test set must contain REAL files.")
|
||||
if data_index:
|
||||
print(data_index, dataloader_len.get(seq_name, "abc"), "4 +++---")
|
||||
if data_index > dataloader_len.get(seq_name, "abc") - 1 or data_index < 0:
|
||||
raise Exception(
|
||||
"Invalid frame id. Help Info: The length of dataloader is {}.".format(
|
||||
dataloader_len.get(seq_name, "abc")))
|
||||
if pipe_path:
|
||||
print(pipe_path, "5 +++---")
|
||||
if os.path.exists(pipe_path) is False:
|
||||
raise Exception(
|
||||
"Invalid .pipeline path. Help Info: please check your .pipeline path.")
|
||||
else:
|
||||
with open(pipe_path, 'rb') as f:
|
||||
pipe_b = f.read()
|
||||
pipe_str = str(pipe_b, encoding='utf-8')
|
||||
pipe_dic = eval(pipe_str)
|
||||
if os.path.exists(
|
||||
pipe_dic['detection0']['mxpi_tensorinfer0']['props']['modelPath']) is False:
|
||||
raise Exception(
|
||||
"Invalid .om path. Help Info: please modify .om path in .pipeline.")
|
||||
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
|
||||
|
||||
def sigmoid(z):
|
||||
return 1.0 / (1.0 + np.exp(-z))
|
||||
|
||||
|
||||
def cross_entropy_with_logits(x, y):
|
||||
return -np.sum(x * np.log(y + 1e-7))
|
||||
|
||||
|
||||
def rooted_mean_squared_error(x, y):
|
||||
mse = 0.5 * np.sum((y - x)**2)
|
||||
return np.sqrt(np.sum(mse)) / len(y)
|
||||
|
||||
|
||||
def do_load(f_name):
|
||||
seqs, dets = [], []
|
||||
with open(f_name) as f:
|
||||
for line in f:
|
||||
seq, tail = line.split(",", 1)
|
||||
seqs.append(int(seq))
|
||||
dets.append(json.loads(tail))
|
||||
return seqs, dets
|
||||
|
||||
|
||||
def save_detections(det_coords, det_scores, occluded):
|
||||
|
||||
if det_scores is None:
|
||||
det_scores = np.ones(len(det_coords), dtype=np.float32)
|
||||
|
||||
if occluded is None:
|
||||
occluded = np.zeros(len(det_coords), dtype=np.int32)
|
||||
|
||||
long_str = ""
|
||||
for cls, xy, occ in zip(det_scores, det_coords, occluded):
|
||||
long_str += f"Pedestrian 0 {occ} 0 0 0 0 0 0 0 0 0 {xy[0]} {xy[1]} 0 0 {cls}\n"
|
||||
long_str = long_str.strip("\n")
|
||||
|
||||
return long_str
|
||||
|
||||
|
||||
def rphi_xy_convertor(rdius, ang):
|
||||
return rdius * np.cos(ang), rdius * np.sin(ang)
|
||||
|
||||
|
||||
|
||||
def nms_predicted_center(
|
||||
scan_grid, phi_grid, pred_cls, pred_reg, min_dist=0.5
|
||||
):
|
||||
assert len(pred_cls.shape) == 1
|
||||
|
||||
tmp_y = scan_grid + pred_reg[:, 1]
|
||||
tmp_phi = np.arctan2(pred_reg[:, 0], tmp_y)
|
||||
dets_phi = tmp_phi + phi_grid
|
||||
dets_r = tmp_y / np.cos(tmp_phi)
|
||||
pred_xs, pred_ys = dets_r * np.cos(dets_phi), dets_r * np.sin(dets_phi)
|
||||
|
||||
# sort prediction with descending confidence
|
||||
sort_inds = np.argsort(pred_cls)[::-1]
|
||||
|
||||
pred_xs, pred_ys = pred_xs[sort_inds], pred_ys[sort_inds]
|
||||
pred_cls = pred_cls[sort_inds]
|
||||
|
||||
# compute pair-wise distance
|
||||
num_pts = len(scan_grid)
|
||||
xdiff = pred_xs.reshape(num_pts, 1) - pred_xs.reshape(1, num_pts)
|
||||
ydiff = pred_ys.reshape(num_pts, 1) - pred_ys.reshape(1, num_pts)
|
||||
p_dist = np.sqrt(np.square(xdiff) + np.square(ydiff))
|
||||
|
||||
# nms
|
||||
keep = np.ones(num_pts, dtype=np.bool_)
|
||||
instance_mask = np.zeros(num_pts, dtype=np.int32)
|
||||
instance_id = 1
|
||||
for i in range(num_pts):
|
||||
if not keep[i]:
|
||||
continue
|
||||
|
||||
dup_inds = p_dist[i] < min_dist
|
||||
keep[dup_inds] = False
|
||||
keep[i] = True
|
||||
instance_mask[sort_inds[dup_inds]] = instance_id
|
||||
instance_id += 1
|
||||
|
||||
det_xys = np.stack((pred_xs, pred_ys), axis=1)[keep]
|
||||
det_cls = pred_cls[keep]
|
||||
|
||||
return det_xys, det_cls, instance_mask # pred_reg_prev being None
|
||||
|
||||
|
||||
def main():
|
||||
parser = argparse.ArgumentParser(description="arg parser")
|
||||
parser.add_argument(
|
||||
"--data_path",
|
||||
type=str,
|
||||
required=True,
|
||||
help="dataset directory.")
|
||||
parser.add_argument(
|
||||
"--pipe_store",
|
||||
type=str,
|
||||
required=True,
|
||||
help="collecting pipeline.")
|
||||
parser.add_argument(
|
||||
"--split",
|
||||
type=str,
|
||||
required=True,
|
||||
help="test, test_nano, or val ")
|
||||
parser.add_argument(
|
||||
"--seq_name",
|
||||
type=str,
|
||||
default=None,
|
||||
help="sequence name for quick test.")
|
||||
parser.add_argument(
|
||||
"--frame_id",
|
||||
type=str,
|
||||
default=None,
|
||||
help="frame index for quick test.")
|
||||
args = parser.parse_args()
|
||||
|
||||
throw_err(args.data_path,
|
||||
True,
|
||||
args.split,
|
||||
args.seq_name,
|
||||
args.frame_id,
|
||||
args.pipe_store)
|
||||
|
||||
dataset_name = os.path.basename(args.data_path)
|
||||
model_name = os.path.basename(args.pipe_store).split('.')[
|
||||
0].split('_')[0].upper()
|
||||
|
||||
start_time = time.time()
|
||||
unseen_frame = False
|
||||
if args.frame_id:
|
||||
if "DROW" in args.data_path:
|
||||
test_dataset = drow_dataset.DROWDataset(
|
||||
split=args.split,
|
||||
data_dir=[args.data_path, args.seq_name],
|
||||
scan_type=model_name)
|
||||
test_loader = [test_dataset.__getitem__(int(args.frame_id))]
|
||||
try:
|
||||
if len(test_loader) == 0:
|
||||
raise Exception(
|
||||
"Sorry we cannot visit this frame at this time.")
|
||||
except Exception as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
if "JRDB" in args.data_path:
|
||||
test_dataset = jrdb_dataset.JRDBDataset(
|
||||
split=args.split,
|
||||
jrdb_split=args.seq_name,
|
||||
data_dir_cfg=args.data_path)
|
||||
frame_url = str(args.frame_id).zfill(6) + ".txt"
|
||||
test_loader = list(
|
||||
filter(
|
||||
lambda test_sample: os.path.basename(
|
||||
test_sample["laser_frame"]["url"].replace(
|
||||
"\\",
|
||||
"/")) == frame_url,
|
||||
test_dataset))
|
||||
print("len of test_loader", len(test_loader))
|
||||
if len(test_loader) == 0:
|
||||
unseen_frame = True
|
||||
num_scans = 1 if model_name == "DROW" else 10
|
||||
scan_url = os.path.join(args.data_path,
|
||||
args.split.split("_")[0] + "_dataset",
|
||||
"lasers",
|
||||
args.seq_name,
|
||||
frame_url)
|
||||
current_frame_idx = int(
|
||||
os.path.basename(scan_url).split(".")[0])
|
||||
frames_list = []
|
||||
for del_idx in range(num_scans, 0, -1):
|
||||
frame_idx = max(0, current_frame_idx - del_idx * 1)
|
||||
laser_url = os.path.join(
|
||||
os.path.dirname(scan_url),
|
||||
str(frame_idx).zfill(6) +
|
||||
".txt").replace(
|
||||
"\\",
|
||||
"/")
|
||||
laser_loaded = np.loadtxt(
|
||||
os.path.join(
|
||||
args.data_path,
|
||||
laser_url),
|
||||
dtype=np.float32)
|
||||
frames_list.append(laser_loaded)
|
||||
|
||||
batch_dict = {}
|
||||
laser_data = np.stack(frames_list, axis=0)
|
||||
|
||||
laser_grid = np.linspace(-np.pi, np.pi,
|
||||
laser_data.shape[1], dtype=np.float32)
|
||||
ct_kwargs = {
|
||||
"win_width": 1.0,
|
||||
"win_depth": 0.5,
|
||||
"num_ct_pts": 56,
|
||||
"pad_val": 29.99,
|
||||
}
|
||||
batch_dict["scans"] = laser_data
|
||||
batch_dict["scan_phi"] = laser_grid
|
||||
batch_dict["input"] = u.trim_the_scans(
|
||||
laser_data, laser_grid, stride=1, **ct_kwargs,)
|
||||
test_loader.append(batch_dict)
|
||||
|
||||
elif args.seq_name:
|
||||
test_loader = get_dataloader(
|
||||
split=args.split,
|
||||
batch_size=1,
|
||||
num_workers=1, # avoid TypeError: Caught TypeError in DataLoader worker process 0
|
||||
shuffle=False,
|
||||
dataset_pth=[args.data_path, args.seq_name],
|
||||
scan_type=model_name,
|
||||
)
|
||||
else:
|
||||
test_loader = get_dataloader(
|
||||
split=args.split, # "val", "test", "test_nano"
|
||||
batch_size=1,
|
||||
num_workers=1, # avoid TypeError: Caught TypeError in DataLoader worker process 0
|
||||
shuffle=False,
|
||||
dataset_pth=args.data_path,
|
||||
scan_type=model_name,
|
||||
)
|
||||
print("len of test_loader", len(test_loader))
|
||||
|
||||
# The following belongs to the SDK Process
|
||||
stream_manager_api0 = StreamManagerApi()
|
||||
# init stream manager
|
||||
ret = stream_manager_api0.InitManager()
|
||||
if ret != 0:
|
||||
print("Failed to init Stream manager, ret=%s" % str(ret))
|
||||
exit()
|
||||
else:
|
||||
print("-----------------创建流管理StreamManager并初始化-----------------")
|
||||
|
||||
# create streams by pipeline config file
|
||||
with open(args.pipe_store, 'rb') as f:
|
||||
print("-----------------正在读取读取pipeline-----------------")
|
||||
pipeline_str = f.read()
|
||||
print("-----------------成功读取pipeline-----------------")
|
||||
|
||||
ret = stream_manager_api0.CreateMultipleStreams(pipeline_str)
|
||||
|
||||
# Print error message
|
||||
if ret != 0:
|
||||
print(
|
||||
"-----------------Failed to create Stream, ret=%s-----------------" %
|
||||
str(ret))
|
||||
else:
|
||||
print(
|
||||
"-----------------Create Stream Successfully, ret=%s-----------------" %
|
||||
str(ret))
|
||||
# Stream name
|
||||
|
||||
stream_name = b'detection0'
|
||||
|
||||
in_plugin_id = 0
|
||||
tb_dict_list = []
|
||||
dets_xy_accum = {}
|
||||
dets_cls_accum = {}
|
||||
dets_inds_accum = {}
|
||||
gts_xy_accum = {}
|
||||
gts_inds_accum = {}
|
||||
fig_dict = {}
|
||||
for count, batch_dict in enumerate(test_loader):
|
||||
if count >= 1e9:
|
||||
break
|
||||
tensor_package_list = MxpiDataType.MxpiTensorPackageList()
|
||||
tensor_package = tensor_package_list.tensorPackageVec.add()
|
||||
tsor = batch_dict.get("input", "abc").astype('<f4')
|
||||
if args.frame_id:
|
||||
tsor = np.expand_dims(tsor, axis=0)
|
||||
try:
|
||||
if tsor.shape[1] != 450 and tsor.shape[1] != 1091:
|
||||
raise AssertionError(
|
||||
"InputTensor shape does not match model inputTensors.")
|
||||
except AssertionError as e:
|
||||
print(repr(e))
|
||||
sys.exit("Program Exist. Welcome to the next use :D\n")
|
||||
array_bytes = tsor.tobytes()
|
||||
data_input = MxDataInput()
|
||||
data_input.data = array_bytes
|
||||
tensor_vec = tensor_package.tensorVec.add()
|
||||
tensor_vec.deviceId = 0
|
||||
tensor_vec.memType = 0
|
||||
for i in tsor.shape:
|
||||
tensor_vec.tensorShape.append(i)
|
||||
tensor_vec.dataStr = data_input.data
|
||||
tensor_vec.tensorDataSize = len(array_bytes)
|
||||
|
||||
key = "appsrc{}".format(in_plugin_id).encode('utf-8')
|
||||
protobuf_vec = InProtobufVector()
|
||||
protobuf = MxProtobufIn()
|
||||
protobuf.key = key
|
||||
protobuf.type = b'MxTools.MxpiTensorPackageList'
|
||||
protobuf.protobuf = tensor_package_list.SerializeToString()
|
||||
protobuf_vec.push_back(protobuf)
|
||||
|
||||
ret = stream_manager_api0.SendProtobuf(
|
||||
stream_name, in_plugin_id, protobuf_vec)
|
||||
# inPluginId currently fixed to 0 indicating the input port number
|
||||
if ret != 0:
|
||||
print("Failed to send data to stream.")
|
||||
exit()
|
||||
|
||||
key_vec = StringVector()
|
||||
key_vec.push_back(b'mxpi_tensorinfer0')
|
||||
infer_result = stream_manager_api0.GetProtobuf(stream_name, 0, key_vec)
|
||||
print("infer_result", infer_result.size())
|
||||
if infer_result.size() == 0:
|
||||
print("infer_result is null")
|
||||
exit()
|
||||
if infer_result[0].errorCode != 0:
|
||||
print("GetProtobuf error. errorCode=%d" % (
|
||||
infer_result[0].errorCode))
|
||||
exit()
|
||||
result = MxpiDataType.MxpiTensorPackageList()
|
||||
result.ParseFromString(infer_result[0].messageBuf)
|
||||
pred_cls = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[0].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[0].tensorShape))
|
||||
pred_reg = np.frombuffer(
|
||||
result.tensorPackageVec[0].tensorVec[1].dataStr,
|
||||
dtype='<f4').reshape(
|
||||
tuple(
|
||||
result.tensorPackageVec[0].tensorVec[1].tensorShape))
|
||||
prediction_shape = result.tensorPackageVec[0].tensorVec[1].tensorShape
|
||||
|
||||
print("Launching eval...")
|
||||
if unseen_frame:
|
||||
print("Skip eval...")
|
||||
break
|
||||
batch_size = len(batch_dict.get("scans", "abc"))
|
||||
|
||||
for ib in range(batch_size):
|
||||
if args.frame_id:
|
||||
scan = batch_dict.get("scans", "abc")
|
||||
scan_phi = batch_dict.get("scan_phi", "abc")
|
||||
tar_cls = batch_dict.get("target_cls", "abc")
|
||||
tar_reg = batch_dict.get("target_reg", "abc")
|
||||
pred_cls_sigmoid = sigmoid(pred_cls.squeeze())
|
||||
det_xy, det_cls, _ = nms_predicted_center(
|
||||
scan[-1], scan_phi, pred_cls_sigmoid, pred_reg.squeeze()) # by batch
|
||||
frame_id = batch_dict.get("frame_id", "abc")
|
||||
frame_id = f"{frame_id:06d}"
|
||||
sequence = batch_dict.get("sequence", "abc")
|
||||
# save det_xy, det_cls for evaluation
|
||||
anns_rphi = batch_dict.get("dets_wp", "abc")
|
||||
if len(anns_rphi) > 0:
|
||||
anns_rphi = np.array(anns_rphi, dtype=np.float32)
|
||||
gts_xy = np.stack(rphi_xy_convertor(
|
||||
anns_rphi[:, 0], anns_rphi[:, 1]), axis=1)
|
||||
gts_occluded = np.logical_not(
|
||||
batch_dict.get("anns_valid_mask", "abc")).astype(
|
||||
np.int32)
|
||||
else:
|
||||
gts_xy = ""
|
||||
else:
|
||||
scan = batch_dict.get("scans", "abc")[ib]
|
||||
scan_phi = batch_dict.get("scan_phi", "abc")[ib]
|
||||
tar_cls = batch_dict.get("target_cls", "abc")[ib]
|
||||
tar_reg = batch_dict.get("target_reg", "abc")[ib]
|
||||
pred_cls_sigmoid = sigmoid(pred_cls[ib].squeeze())
|
||||
det_xy, det_cls, _ = nms_predicted_center(
|
||||
scan[-1], scan_phi, pred_cls_sigmoid, pred_reg[ib]) # by batch
|
||||
frame_id = batch_dict.get("frame_id", "abc")[ib]
|
||||
frame_id = f"{frame_id:06d}"
|
||||
sequence = batch_dict.get("sequence", "abc")[ib]
|
||||
# save det_xy, det_cls for evaluation
|
||||
anns_rphi = batch_dict.get("dets_wp", "abc")[ib]
|
||||
if len(anns_rphi) > 0:
|
||||
anns_rphi = np.array(anns_rphi, dtype=np.float32)
|
||||
gts_xy = np.stack(rphi_xy_convertor(
|
||||
anns_rphi[:, 0], anns_rphi[:, 1]), axis=1)
|
||||
gts_occluded = np.logical_not(
|
||||
batch_dict.get("anns_valid_mask", "abc")[ib]).astype(
|
||||
np.int32)
|
||||
else:
|
||||
gts_xy = ""
|
||||
if "JRDB" in args.data_path:
|
||||
seq_nname = args.seq_name if args.seq_name else args.split
|
||||
det_str = save_detections(
|
||||
det_xy, det_cls, None)
|
||||
det_fname = os.path.join(
|
||||
os.getcwd(),
|
||||
f"outputs_{dataset_name}_{seq_nname}_{model_name}/detections/{sequence}/{frame_id}.txt")
|
||||
os.makedirs(os.path.dirname(det_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(det_fname, FLAGS, MODES), "w") as fdo:
|
||||
fdo.write(det_str)
|
||||
gts_str = save_detections(
|
||||
gts_xy, None, gts_occluded)
|
||||
gts_fname = os.path.join(
|
||||
os.getcwd(),
|
||||
f"outputs_{dataset_name}_{seq_nname}_{model_name}/groundtruth/{sequence}/{frame_id}.txt")
|
||||
os.makedirs(os.path.dirname(gts_fname), exist_ok=True)
|
||||
with os.fdopen(os.open(gts_fname, FLAGS, MODES), "w") as fgo:
|
||||
fgo.write(gts_str)
|
||||
|
||||
if len(det_xy) > 0: # if not empty
|
||||
try:
|
||||
if sequence not in list(dets_cls_accum.keys()):
|
||||
dets_xy_accum[sequence] = []
|
||||
dets_cls_accum[sequence] = []
|
||||
dets_inds_accum[sequence] = []
|
||||
dets_xy_accum[sequence].append(det_xy)
|
||||
dets_cls_accum[sequence].append(det_cls)
|
||||
dets_inds_accum[sequence] += [frame_id] * len(det_xy)
|
||||
except KeyError:
|
||||
print("Dict KeyError!")
|
||||
|
||||
if len(gts_xy) > 0: # if not empty
|
||||
try:
|
||||
if sequence not in list(gts_xy_accum.keys()):
|
||||
gts_xy_accum[sequence], gts_inds_accum[sequence] = [], []
|
||||
gts_xy_accum[sequence].append(gts_xy)
|
||||
gts_inds_accum[sequence] += [frame_id] * len(gts_xy)
|
||||
except KeyError:
|
||||
print("Dict KeyError!")
|
||||
|
||||
# do the following in batch
|
||||
tar_shape = np.prod(batch_dict.get("target_cls", "abc").shape)
|
||||
|
||||
tar_cls = tar_cls.reshape(tar_shape)
|
||||
pred_cls = pred_cls.reshape(tar_shape)
|
||||
|
||||
# evaluate
|
||||
if "DROW" in args.data_path or args.frame_id is not None:
|
||||
for key in [*dets_cls_accum]:
|
||||
dets_xy = np.concatenate(dets_xy_accum.get(key, "abc"), axis=0)
|
||||
dets_cls = np.concatenate(dets_cls_accum.get(key, "abc"))
|
||||
dets_inds = np.array(dets_inds_accum.get(key, "abc"))
|
||||
gts_xy = np.concatenate(gts_xy_accum.get(key, "abc"), axis=0)
|
||||
gts_inds = np.array(gts_inds_accum.get(key, "abc"))
|
||||
# evaluate all sequences
|
||||
seq03, seq05 = [], []
|
||||
try:
|
||||
seq03.append(
|
||||
pru.eval_internal(
|
||||
dets_xy,
|
||||
dets_cls,
|
||||
dets_inds,
|
||||
gts_xy,
|
||||
gts_inds,
|
||||
ar=0.3))
|
||||
except AssertionError as e:
|
||||
print(repr(e))
|
||||
try:
|
||||
seq05.append(
|
||||
pru.eval_internal(
|
||||
dets_xy,
|
||||
dets_cls,
|
||||
dets_inds,
|
||||
gts_xy,
|
||||
gts_inds,
|
||||
ar=0.5))
|
||||
except AssertionError as e:
|
||||
print(repr(e))
|
||||
if len(seq03) > 0 and len(seq05) > 0:
|
||||
print(f"Evaluating {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq03[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq03[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq03[-1]['eer']:4f}\n"
|
||||
f"AP_0.5 {seq05[-1]['ap']:4f} "
|
||||
f"peak-F1_0.5 {seq05[-1]['peak_f1']:4f} "
|
||||
f"EER_0.5 {seq05[-1]['eer']:4f}\n"
|
||||
)
|
||||
elif len(seq03) > 0:
|
||||
print(f"Evaluating ar=0.3 {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq03[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq03[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq03[-1]['eer']:4f}\n"
|
||||
)
|
||||
elif len(seq05) > 0:
|
||||
print(f"Evaluating ar=0.5 {key} {args.frame_id}")
|
||||
print(
|
||||
f"AP_0.3 {seq05[-1]['ap']:4f} "
|
||||
f"peak-F1_0.3 {seq05[-1]['peak_f1']:4f} "
|
||||
f"EER_0.3 {seq05[-1]['eer']:4f}\n"
|
||||
)
|
||||
|
||||
end_time = time.time()
|
||||
print("FPS:", len(test_loader) / (end_time - start_time))
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
Reference in New Issue
Block a user