数据集来源:https://oxford-robotics-institute.github.io/radar-robotcar-dataset/documentation
雷达是 Navtech CTS350-X 调频连续波 (FMCW) 扫描雷达,在所使用的配置中提供 4.38 cm 的距离分辨率和 0.9 度的旋转分辨率,范围高达 163 m,同时提供对天气条件的稳健性这可能会给其他传感器模式带来麻烦。在其他配置中,Navtech CTS350-X 可以提供超过 650 m 的范围和更高的旋转速度。然而,对于城市环境,更高的分辨率是更可取的。
车辆传感器所在位置示意图如下
车顶一个Bumblebee XB3相机,一个毫米波雷达CTS350,雷达左右各一个HDL-32E激光雷达;
车前后各一个LMS-151激光雷达,车尾三个Grasshopper相机(紫色),一个SPAN-CPT GPS。
Cameras:
1 x Point Grey Bumblebee XB3
3 x Point Grey Grasshopper2
LIDAR:
2 x SICK LMS-151 2D LIDAR
GPS/INS:
1 x NovAtel SPAN-CPT ALIGN inertial and GPS navigation system
As well as additionally collecting:
Radar:
1 x Navtech CTS350-X - Mounted in the centre of the roof aligned with the vehicles axes.
LIDAR
2 x Velodyne HDL-32E - Mounted to the left and right of the Navtech CTS350-X radar.
雷达数据以极坐标格式的无损 PNG 文件形式发布,每行代表每个方位角的传感器读数(在程序中azimuth为一个(400,1)的矩阵),每列代表特定范围内的原始功率返回(在程序中fft_data是(400,3768,1))。在使用的配置中,每次扫描有 400 个方位角(行)和 3768 个距离区间(列)。这些文件的结构为radar/.png,其中 是捕获的起始UNIX 时间戳,以微秒为单位。
为了向用户提供他们可能需要的所有原始数据,我们还将以下每个方位角元数据嵌入到 PNG 文件的前 11 列中:
UNIX 时间戳在第 1-8 列中为 int64
在第 9-10 列中作为 uint16 的扫描计数器 - 转换为具有方位角的角度(弧度)=扫描计数器 / 编码器大小 * 2 * pi,其中我们的配置编码器大小固定为 5600。
在第 11 列中作为 uint8 的有效标志 - 很少会从 Navtech 雷达中丢弃极少量携带方位角回波的数据包。为了简化用户的使用,我们对相邻回波进行了插值,以便提供的每个雷达扫描具有 400 个方位角。如果这是不可取的,只需删除有效标志设置为零的任何行。
学习重点:
官方给的程序代码
################################################################################
#
# Copyright (c) 2017 University of Oxford
# Authors:
# Dan Barnes ([email protected])
#
# This work is licensed under the Creative Commons
# Attribution-NonCommercial-ShareAlike 4.0 International License.
# To view a copy of this license, visit
# http://creativecommons.org/licenses/by-nc-sa/4.0/ or send a letter to
# Creative Commons, PO Box 1866, Mountain View, CA 94042, USA.
#
################################################################################
import argparse
import os
from radar import load_radar, radar_polar_to_cartesian ##定义的radar.py中的函数,见下一段代码
import numpy as np
import cv2
##找需要显示的radar数据文件
parser = argparse.ArgumentParser(description='Play back radar data from a given directory')
parser.add_argument('dir', type=str, help='Directory containing radar data.')
args = parser.parse_args()
timestamps_path = os.path.join(os.path.join(args.dir, os.pardir, 'radar.timestamps'))
if not os.path.isfile(timestamps_path):
raise IOError("Could not find timestamps file")
#设置笛卡尔可视化参数,分辨率以及显示的长宽
# Cartesian Visualsation Setup
# Resolution of the cartesian form of the radar scan in metres per pixel
cart_resolution = .25
# Cartesian visualisation size (used for both height and width)
cart_pixel_width = 501 # pixels
interpolate_crossover = True
title = "Radar Visualisation Example"
radar_timestamps = np.loadtxt(timestamps_path, delimiter=' ', usecols=[0], dtype=np.int64)
for radar_timestamp in radar_timestamps:
filename = os.path.join(args.dir, str(radar_timestamp) + '.png')
if not os.path.isfile(filename):
raise FileNotFoundError("Could not find radar example: {}".format(filename))
timestamps, azimuths, valid, fft_data, radar_resolution = load_radar(filename)#radar.py中的内容
cart_img = radar_polar_to_cartesian(azimuths, fft_data, radar_resolution, cart_resolution, cart_pixel_width,
interpolate_crossover)#极坐标转换为雷达坐标
# Combine polar and cartesian for visualisation
# The raw polar data is resized to the height of the cartesian representation
downsample_rate = 4#下采样率
fft_data_vis = fft_data[:, ::downsample_rate]
resize_factor = float(cart_img.shape[0]) / float(fft_data_vis.shape[0])
fft_data_vis = cv2.resize(fft_data_vis, (0, 0), None, resize_factor, resize_factor)
vis = cv2.hconcat((fft_data_vis, fft_data_vis[:, :10] * 0 + 1, cart_img))
cv2.imshow(title, vis * 2.) # The data is doubled to improve visualisation数据翻倍以改善可视化
cv2.waitKey(1)
################################################################################
#
# Copyright (c) 2017 University of Oxford
# Authors:
# Dan Barnes ([email protected])
#
# This work is licensed under the Creative Commons
# Attribution-NonCommercial-ShareAlike 4.0 International License.
# To view a copy of this license, visit
# http://creativecommons.org/licenses/by-nc-sa/4.0/ or send a letter to
# Creative Commons, PO Box 1866, Mountain View, CA 94042, USA.
#
###############################################################################
from typing import AnyStr, Tuple
import numpy as np
import cv2
def load_radar(example_path: AnyStr) -> Tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarray, float]:
"""Decode a single Oxford Radar RobotCar Dataset radar example
Args:
example_path (AnyStr): Oxford Radar RobotCar Dataset Example png
Returns:
timestamps (np.ndarray): Timestamp for each azimuth in int64 (UNIX time)
azimuths (np.ndarray): Rotation for each polar radar azimuth (radians)
valid (np.ndarray) Mask of whether azimuth data is an original sensor reading or interpolated from adjacent
azimuths
fft_data (np.ndarray): Radar power readings along each azimuth
radar_resolution (float): Resolution of the polar radar data (metres per pixel)
"""
# Hard coded configuration to simplify parsing code
radar_resolution = np.array([0.0432], np.float32)
encoder_size = 5600
raw_example_data = cv2.imread(example_path, cv2.IMREAD_GRAYSCALE)
timestamps = raw_example_data[:, :8].copy().view(np.int64)
azimuths = (raw_example_data[:, 8:10].copy().view(np.uint16) / float(encoder_size) * 2 * np.pi).astype(np.float32)
#在第 9-10 列中作为 uint16 的扫描计数器 - 转换为具有方位角的角度(弧度)=扫描计数器 / 编码器大小 * 2 * pi,其中我们的配置编码器大小固定为 5600。
valid = raw_example_data[:, 10:11] == 255
#在第 11 列中作为 uint8 的有效标志 - 很少会从 Navtech 雷达中丢弃极少量携带方位角回波的数据包。为了简化用户的使用,我们对相邻回波进行了插值,以便提供的每个雷达扫描具有 400 个方位角。如果这是不可取的,只需删除有效标志设置为零的任何行。
fft_data = raw_example_data[:, 11:].astype(np.float32)[:, :, np.newaxis] / 255.
##Polar radar power readings
return timestamps, azimuths, valid, fft_data, radar_resolution
def radar_polar_to_cartesian(azimuths: np.ndarray, fft_data: np.ndarray, radar_resolution: float,
cart_resolution: float, cart_pixel_width: int, interpolate_crossover=True) -> np.ndarray:
"""Convert a polar radar scan to cartesian.
Args:
azimuths (np.ndarray): Rotation for each polar radar azimuth (radians)
fft_data (np.ndarray): Polar radar power readings
radar_resolution (float): Resolution of the polar radar data (metres per pixel)
cart_resolution (float): Cartesian resolution (metres per pixel)
cart_pixel_size (int): Width and height of the returned square cartesian output (pixels). Please see the Notes
below for a full explanation of how this is used.
interpolate_crossover (bool, optional): If true interpolates between the end and start azimuth of the scan. In
practice a scan before / after should be used but this prevents nan regions in the return cartesian form.
interpolate_crossover (bool, optional): 如果为真,则在扫描的结束和开始方位角之间进行插值。在应该使用之前/之后的扫描练习,但这可以防止返回笛卡尔形式的 nan 区域。
Returns:
np.ndarray: Cartesian radar power readings
Notes:
After using the warping grid the output radar cartesian is defined as as follows where
X and Y are the `real` world locations of the pixels in metres:
#X 和 Y 是以米为单位的像素的“真实”世界位置:
If 'cart_pixel_width' is odd:
如果是奇数
+------ Y = -1 * cart_resolution (m)
|+----- Y = 0 (m) at centre pixel
||+---- Y = 1 * cart_resolution (m)
|||+--- Y = 2 * cart_resolution (m)
|||| +- Y = cart_pixel_width // 2 * cart_resolution (m) (at last pixel)
|||| +-----------+
vvvv v
+---------------+---------------+
| | |
| | |
| | |
| | |
| | |
| | |
| | |
+---------------+---------------+ <-- X = 0 (m) at centre pixel
| | |
| | |
| | |
| | |
| | |
| | |
| | |
+---------------+---------------+
<------------------------------->
cart_pixel_width (pixels)
If 'cart_pixel_width' is even:
如果是偶数
+------ Y = -0.5 * cart_resolution (m)
|+----- Y = 0.5 * cart_resolution (m)
||+---- Y = 1.5 * cart_resolution (m)
|||+--- Y = 2.5 * cart_resolution (m)
|||| +- Y = (cart_pixel_width / 2 - 0.5) * cart_resolution (m) (at last pixel)
|||| +----------+
vvvv v
+------------------------------+
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
+------------------------------+
<------------------------------>
cart_pixel_width (pixels)
"""
if (cart_pixel_width % 2) == 0:
cart_min_range = (cart_pixel_width / 2 - 0.5) * cart_resolution
else:
cart_min_range = cart_pixel_width // 2 * cart_resolution
coords = np.linspace(-cart_min_range, cart_min_range, cart_pixel_width, dtype=np.float32)
Y, X = np.meshgrid(coords, -coords)
sample_range = np.sqrt(Y * Y + X * X)
sample_angle = np.arctan2(Y, X)
sample_angle += (sample_angle < 0).astype(np.float32) * 2. * np.pi
# Interpolate Radar Data Coordinates内插雷达数据坐标
azimuth_step = azimuths[1] - azimuths[0]
sample_u = (sample_range - radar_resolution / 2) / radar_resolution
sample_v = (sample_angle - azimuths[0]) / azimuth_step
# We clip the sample points to the minimum sensor reading range so that we
# do not have undefined results in the centre of the image. In practice
# this region is simply undefined.
#我们将样本点剪辑到最小传感器读数范围,以便我们在图像的中心没有未定义的结果。
sample_u[sample_u < 0] = 0
if interpolate_crossover:
fft_data = np.concatenate((fft_data[-1:], fft_data, fft_data[:1]), 0)
sample_v = sample_v + 1
polar_to_cart_warp = np.stack((sample_u, sample_v), -1)
cart_img = np.expand_dims(cv2.remap(fft_data, polar_to_cart_warp, None, cv2.INTER_LINEAR), -1)
return cart_img
详细见:
https://zhuanlan.zhihu.com/p/56922793
argsparse是python的命令行解析的标准模块,内置于python,不需要安装。这个库可以让我们直接在命令行中就可以向程序中传入参数并让程序运行。
import argparse
parser = argparse.ArgumentParser(description='命令行中传入一个数字')
#type是要传入的参数的数据类型 help是该参数的提示信息
parser.add_argument('integers', type=str, help='传入的数字')
args = parser.parse_args()
#获得传入的参数
print(args)
基础知识学习:
https://www.cnblogs.com/silence-cho/p/10926248.html
一些主要函数:
imread(img_path,flag) 读取图片,返回图片对象
img_path: 图片的路径,即使路径错误也不会报错,但打印返回的图片对象为None
flag:cv2.IMREAD_COLOR,读取彩色图片,图片透明性会被忽略,为默认参数,也可以传入1
cv2.IMREAD_GRAYSCALE,按灰度模式读取图像,也可以传入0
cv2.IMREAD_UNCHANGED,读取图像,包括其alpha通道,也可以传入-1
这里用到的是黑白图像
imshow(window_name,img):显示图片,窗口自适应图片大小
window_name: 指定窗口的名字
img:显示的图片对象
可以指定多个窗口名称,显示多个图片
waitKey(millseconds) 键盘绑定事件,阻塞监听键盘按键,返回一个数字(不同按键对应的数字不同)
millseconds: 传入时间毫秒数,在该时间内等待键盘事件;传入0时,会一直等待键盘事件
destroyAllWindows(window_name)
window_name: 需要关闭的窗口名字,不传入时关闭所有窗口
系列培训视频,见B站:
https://www.bilibili.com/video/BV1k4411C7aW?p=7
mmwave
FMCW表示调频连续波
该雷达主要测量前方物体的距离、速度和到达角。核心是用傅里叶变换去计算距离,速度和到达角信息。
笛卡尔坐标系(Cartesian coordinates,法语:les coordonnées cartésiennes)就是直角坐标系和斜坐标系的统称。
相交于原点的两条数轴,构成了平面仿射坐标系 。如两条数轴上的度量单位相等,则称此仿射坐标系为笛卡尔坐标系。两条数轴互相垂直的笛卡尔坐标系,称为笛卡尔直角坐标系,否则称为笛卡尔斜角坐标系。