图像API#
如果您不熟悉AirSim API,请先阅读通用API文档。
获取单张图像#
以下是获取名为“0”的相机单张图像的示例代码。返回值是png格式图像的字节。要获取未压缩和其他格式以及可用相机,请参阅下一节。
Python#
import airsim #pip install airsim
# for car use CarClient()
client = airsim.MultirotorClient()
png_image = client.simGetImage("0", airsim.ImageType.Scene)
# do something with image
C++#
#include "vehicles/multirotor/api/MultirotorRpcLibClient.hpp"
int getOneImage()
{
using namespace msr::airlib;
// for car use CarRpcLibClient
MultirotorRpcLibClient client;
std::vector<uint8_t> png_image = client.simGetImage("0", VehicleCameraBase::ImageType::Scene);
// do something with images
}
更灵活地获取图像#
simGetImages
API比simGetImage
API使用起来稍微复杂一些,例如,您可以在一次API调用中获取左相机视图、右相机视图和左相机的深度图像。simGetImages
API还允许您获取未压缩图像以及浮点单通道图像(而不是3通道(RGB),每个8位)。
Python#
import airsim #pip install airsim
# for car use CarClient()
client = airsim.MultirotorClient()
responses = client.simGetImages([
# png format
airsim.ImageRequest(0, airsim.ImageType.Scene),
# uncompressed RGB array bytes
airsim.ImageRequest(1, airsim.ImageType.Scene, False, False),
# floating point uncompressed image
airsim.ImageRequest(1, airsim.ImageType.DepthPlanar, True)])
# do something with response which contains image data, pose, timestamp etc
将AirSim图像与NumPy结合使用#
如果您打算使用numpy进行图像处理,您应该获取未压缩的RGB图像,然后像这样转换为numpy
responses = client.simGetImages([airsim.ImageRequest("0", airsim.ImageType.Scene, False, False)])
response = responses[0]
# get numpy array
img1d = np.fromstring(response.image_data_uint8, dtype=np.uint8)
# reshape array to 4 channel image array H X W X 4
img_rgb = img1d.reshape(response.height, response.width, 3)
# original image is fliped vertically
img_rgb = np.flipud(img_rgb)
# write to png
airsim.write_png(os.path.normpath(filename + '.png'), img_rgb)
快速提示#
-
API
simGetImage
返回binary string literal
,这意味着您可以直接将其转储到二进制文件中以创建 .png 文件。但是,如果您想以任何其他方式处理它,您可以使用便捷函数airsim.string_to_uint8_array
。这会将二进制字符串文字转换为 NumPy uint8 数组。 -
API
simGetImages
可以在一次调用中接受来自任何相机的多种图像类型的请求。您可以指定图像是png压缩、RGB未压缩还是浮点数组。对于png压缩图像,您将获得binary string literal
。对于浮点数组,您将获得 Python 的 float64 列表。您可以使用以下方式将此浮点数组转换为 NumPy 2D 数组
您还可以使用airsim.list_to_2d_float_array(response.image_data_float, response.width, response.height)
airsim.write_pfm()
函数将浮点数组保存到 .pfm 文件(可移植浮点映射格式)。 -
如果您希望在调用某个图像API的同时查询位置和方向信息,可以使用
client.simPause(True)
和client.simPause(False)
在调用图像API和查询所需物理状态时暂停模拟,确保在图像API调用后物理状态保持不变。
C++#
int getStereoAndDepthImages()
{
using namespace msr::airlib;
typedef VehicleCameraBase::ImageRequest ImageRequest;
typedef VehicleCameraBase::ImageResponse ImageResponse;
typedef VehicleCameraBase::ImageType ImageType;
// for car use
// CarRpcLibClient client;
MultirotorRpcLibClient client;
// get right, left and depth images. First two as png, second as float16.
std::vector<ImageRequest> request = {
//png format
ImageRequest("0", ImageType::Scene),
//uncompressed RGB array bytes
ImageRequest("1", ImageType::Scene, false, false),
//floating point uncompressed image
ImageRequest("1", ImageType::DepthPlanar, true)
};
const std::vector<ImageResponse>& response = client.simGetImages(request);
// do something with response which contains image data, pose, timestamp etc
}
可直接运行的完整示例#
Python#
有关更完整的、可直接运行的示例代码,请参阅多旋翼的 AirSimClient项目中的示例代码 或 HelloCar示例。此代码还演示了将图像保存到文件或使用 numpy
处理图像等简单活动。
C++#
有关更完整的、可直接运行的示例代码,请参阅多旋翼的 HelloDrone项目中的示例代码 或 HelloCar项目。
另请参阅 其他示例代码,该代码生成指定数量的立体图像以及真实深度和视差,并将其保存为 pfm 格式。
可用相机#
这些是每个载具中已有的默认相机。除此之外,您可以通过设置为载具添加更多相机以及不附着于任何载具的外部相机。
汽车#
汽车上的相机可以通过API调用中的以下名称访问:front_center
、front_right
、front_left
、fpv
和 back_center
。这里的FPV相机是驾驶员在车内的头部位置。
多旋翼#
无人机上的相机可以通过API调用中的以下名称访问:front_center
、front_right
、front_left
、bottom_center
和 back_center
。
计算机视觉模式#
相机名称与多旋翼的相同。
相机名称的向后兼容性#
在 AirSim v1.2 之前,相机是使用 ID 号而不是名称访问的。为了向后兼容,您仍然可以使用以下 ID 号来表示上述相机名称,顺序与上述相同:"0"
、"1"
、"2"
、"3"
、"4"
。此外,相机名称 ""
也可用于访问默认相机,通常是相机 "0"
。
“计算机视觉”模式#
您可以在所谓的“计算机视觉”模式下使用AirSim。在此模式下,物理引擎被禁用,没有载具,只有相机(如果您希望拥有载具但没有其运动学,您可以使用多旋翼模式,并将物理引擎设置为外部物理引擎)。您可以使用键盘移动(按F1查看按键帮助)。您可以按录制按钮连续生成图像。或者您可以调用API来移动相机并拍摄图像。
要激活此模式,请编辑您的 Documents\AirSim
文件夹(或 Linux 上的 ~/Documents/AirSim
)中的 settings.json,并确保以下值存在于根级别
{
"SettingsVersion": 1.2,
"SimMode": "ComputerVision"
}
这里是 Python 代码示例,用于移动相机并捕获图像。
此模式的灵感来自 UnrealCV 项目。
在计算机视觉模式下设置姿态#
要使用 API 在环境中移动,您可以使用 simSetVehiclePose
API。此 API 接受位置和方向,并将其设置在无形载具上,该载具位于前置中心摄像机的位置。所有其他摄像机都保持相对位置移动。如果您不想改变位置(或方向),只需将位置(或方向)的组件设置为浮点 nan 值即可。simGetVehiclePose
允许检索当前姿态。您还可以使用 simGetGroundTruthKinematics
获取运动的物理量。许多其他非载具特定 API 也可用,例如分割 API、碰撞 API 和摄像机 API。
相机API#
simGetCameraInfo
返回指定相机的姿态(在世界坐标系中,NED坐标,SI单位)和视野(以度为单位)。请参阅示例用法。
simSetCameraPose
设置指定相机的姿态,将输入姿态作为 NED 框架中相对位置和四元数的组合。便捷的 airsim.to_quaternion()
函数允许将俯仰、滚转、偏航转换为四元数。例如,要将相机 0 设置为 15 度俯仰,同时保持相同位置,可以使用
camera_pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0.261799, 0, 0)) #PRY in radians
client.simSetCameraPose(0, camera_pose);
simSetCameraFov
允许在运行时改变相机的视野。simSetDistortionParams
、simGetDistortionParams
允许设置和获取畸变参数 K1、K2、K3、P1、P2
所有相机API除了API特定的参数外,还接受3个常用参数:camera_name
(字符串)、vehicle_name
(字符串)和external
(布尔值,表示外部相机)。相机和载具名称用于获取特定相机,如果external
设置为true
,则载具名称将被忽略。另请参阅external_camera.py以获取这些API的示例用法。
云台#
您可以使用设置为任何相机设置俯仰、滚转或偏航的稳定功能。
请参阅示例用法。
更改分辨率和相机参数#
要更改分辨率、视场角等,您可以使用 settings.json。例如,在 settings.json 中添加以下内容将设置场景捕获参数并使用上述“计算机视觉”模式。如果您省略任何设置,将使用以下默认值。有关更多信息,请参阅 settings 文档。如果您使用的是立体相机,目前左右相机之间的距离固定为 25 厘米。
{
"SettingsVersion": 1.2,
"CameraDefaults": {
"CaptureSettings": [
{
"ImageType": 0,
"Width": 256,
"Height": 144,
"FOV_Degrees": 90,
"AutoExposureSpeed": 100,
"MotionBlurAmount": 0
}
]
},
"SimMode": "ComputerVision"
}
不同图像类型中像素值的含义是什么?#
可用ImageType值#
Scene = 0,
DepthPlanar = 1,
DepthPerspective = 2,
DepthVis = 3,
DisparityNormalized = 4,
Segmentation = 5,
SurfaceNormals = 6,
Infrared = 7,
OpticalFlow = 8,
OpticalFlowVis = 9
深度平面和深度透视#
通常您希望将深度图像检索为浮点数(即设置 pixels_as_float = true
)并在 ImageRequest
中指定 ImageType = DepthPlanar
或 ImageType = DepthPerspective
。对于 ImageType = DepthPlanar
,您获取的是相机平面中的深度,即与相机平面平行的所有点具有相同的深度。对于 ImageType = DepthPerspective
,您通过击中该像素的投影光线从相机获取深度。根据您的用例,平面深度或透视深度可能是您想要的真实图像。例如,您可以将透视深度馈送给 ROS 包,例如 depth_image_proc
以生成点云。或者平面深度可能与立体算法(例如 SGM)生成的估计深度图像更兼容。
深度可视化#
当您在 ImageRequest
中指定 ImageType = DepthVis
时,您会得到一张有助于深度可视化的图像。在这种情况下,每个像素值会根据相机平面中以米为单位的深度从黑色到白色进行插值。纯白色像素表示深度为 100 米或更深,而纯黑色像素表示深度为 0 米。
视差归一化#
通常您希望将视差图像检索为浮点数(即设置 pixels_as_float = true
并在 ImageRequest
中指定 ImageType = DisparityNormalized
),在这种情况下,每个像素的值为 (Xl - Xr)/Xmax
,从而归一化到 0 到 1 之间。
分割#
当您在 ImageRequest
中指定 ImageType = Segmentation
时,您会获得一张提供场景真实分割的图像。在启动时,AirSim 会为环境中每个可用网格分配 0 到 255 的值。此值随后会映射到 调色板 中的特定颜色。每个对象 ID 的 RGB 值可以在 此文件 中找到。
您可以使用API为特定网格分配一个特定值(限制在0-255范围内)。例如,下面的Python代码将Blocks环境中名为“Ground”的网格的对象ID设置为20,从而更改其在分割视图中的颜色
success = client.simSetSegmentationObjectID("Ground", 20);
返回值为布尔类型,告知您是否找到了网格。
请注意,典型的虚幻环境(如 Blocks)通常有许多其他构成相同对象的网格,例如“Ground_2”、“Ground_3”等。由于为所有这些网格设置对象 ID 既繁琐又耗时,AirSim 还支持正则表达式。例如,以下代码只需一行即可将所有名称以“ground”开头(忽略大小写)的网格设置为 21
success = client.simSetSegmentationObjectID("ground[\w]*", 21, True);
如果使用正则表达式匹配至少找到一个网格,则返回值为 true。
建议您使用此 API 请求未压缩图像,以确保获得精确的分割图像 RGB 值
responses = client.simGetImages([ImageRequest(0, AirSimImageType.Segmentation, False, False)])
img1d = np.fromstring(response.image_data_uint8, dtype=np.uint8) #get numpy array
img_rgb = img1d.reshape(response.height, response.width, 3) #reshape array to 3 channel image array H X W X 3
img_rgb = np.flipud(img_rgb) #original image is fliped vertically
#find unique colors
print(np.unique(img_rgb[:,:,0], return_counts=True)) #red
print(np.unique(img_rgb[:,:,1], return_counts=True)) #green
print(np.unique(img_rgb[:,:,2], return_counts=True)) #blue
可以在 segmentation.py 中找到一个完整的、可直接运行的示例。
取消设置对象ID#
对象ID可以设置为-1,使其不显示在分割图像上。
如何查找网格名称?#
要获得所需的真实分割,您需要了解虚幻环境中的网格名称。为此,您需要在虚幻编辑器中打开虚幻环境,然后使用世界大纲视图检查您感兴趣的网格名称。例如,下面我们在编辑器右侧面板中看到 Blocks 环境中地面的网格名称
如果您不知道如何在虚幻编辑器中打开虚幻环境,请尝试遵循从源代码构建的指南。
一旦您确定了感兴趣的网格,记下它们的名称并使用上述 API 设置它们的物体 ID。有一些设置可用于更改物体 ID 的生成行为。
更改对象ID的颜色#
目前,每个对象ID的颜色都是固定的,如此调色板所示。我们很快将添加更改对象ID颜色为所需值的功能。在此期间,您可以在您喜欢的图像编辑器中打开分割图像,并获取您感兴趣的RGB值。
启动对象ID#
在启动时,AirSim 会为环境中找到的每个 UStaticMeshComponent
或 ALandscapeProxy
类型的对象分配对象 ID。然后,它会使用网格名称或所有者名称(取决于设置),将其转换为小写,移除 ASCII 97 以下的所有字符以移除数字和一些标点符号,对所有字符的整数值求和,并模 255 生成对象 ID。换句话说,所有具有相同字母字符的对象将获得相同的对象 ID。这种启发式方法简单有效,适用于许多虚幻环境,但可能不是您想要的。在这种情况下,请使用上述 API 将对象 ID 更改为您想要的值。有一些设置可用于更改此行为。
获取网格的对象ID#
simGetSegmentationObjectID
API 允许您获取给定网格名称的对象 ID。
红外#
目前,这只是从对象 ID 到灰度 0-255 的映射。因此,任何对象 ID 为 42 的网格都显示为颜色 (42, 42, 42)。有关如何设置对象 ID 的更多详细信息,请参阅分割部分。通常,可以对此图像类型应用噪声设置以获得稍微更真实的效果。我们仍在努力添加其他红外伪影,欢迎任何贡献。
光流和光流可视化#
这些图像类型返回相机视点感知到的运动信息。OpticalFlow 返回一个双通道图像,其中通道分别对应 vx 和 vy。OpticalFlowVis 类似于 OpticalFlow,但将光流数据转换为 RGB 以获得更“可视化”的输出。
示例代码#
可以在 GenerateImageGenerator.hpp 中找到一个完整的示例,该示例设置随机位置和方向的车辆姿态,然后拍摄图像。此示例生成指定数量的立体图像和真实视差图像,并将其保存为 pfm 格式。