无人机姿态角

Java 无人机 推流 无人机api接口_API

pitch是俯仰角,是“点头“

yaw是偏航角,是‘摇头’

roll是旋转角,是“翻滚”

Java 无人机 推流 无人机api接口_Java 无人机 推流_02

  • 四旋翼参数:C:\AirSim\AirLib\include\vehicles\multirotor\firmwares\mavlink\ArduCopterSoloParams.hpp
  • 螺旋桨电机参数:C:\AirSim\AirLib\include\vehicles\multirotor\RotorParams.hpp
  • 控制参数:C:\AirSim\AirLib\include\vehicles\multirotor\firmwares\simple_flight\firmware\Params.hpp

通信机制

AirSim API 使用的是 TCP/IP 中的 msgpack-rpc 协议,这是一种网络通信协议。当 AirSim 开始仿真的时候,会打开 41451 端口,并监听这个端口的需求。python 程序使用 msgpack serialization 格式向这个端口发送 RPC 包,就可以与AirSim进行通信了。可以通过 settings 文件改变AirSim使用的端口号。使用这种网络通信协议的方式,可以将 AirSim 和 python程序隔离,互不干扰。即使python程序中断了,AirSim 的仿真也可以继续进行。

API

建立连接

import airsim  # 导入airsim包

基础操作

client = airsim.MultirotorClient()  # 与airsim建立连接,并返回句柄
client.confirmConnection()
client.enableApiControl(True)  # 获取控制权
client.enableApiControl(False)   # 释放控制权
client.armDisarm(True)  # 解锁
client.armDisarm(False)   # 上锁
client.takeoffAsync().join()  #起飞 .join()等待任务执行完毕
# client.landAsync().join()  # 降落
client.hoverAsync().join()

很多无人机或者汽车控制的函数都有 Async 作为后缀,这些函数在执行的时候会立即返回,这样的话,虽然任务还没有执行完,但是程序可以继续执行下去,而不用等待这个函数的任务在仿真中有没有执行完。

如果你想让程序在这里等待任务执行完,则只需要在后面加上.join()。本例子就是让程序在这里等待无人机起飞任务完成,然后再执行降落任务。

新的任务会打断上一个没有执行完的任务,如果不加.join()后缀,则不用等待任务是否完成,函数直接返回,程序继续往下执行。所以如果takeoff函数没有加 .join(),则最后的表现是无人机还没有起飞就降落了,无人机是不会起飞的。

.join()就是需要等上一个任务执行完再执行,Async则是函数执行立即返回读下一条任务。

飞行控制API

当四旋翼低速飞行时,其底层飞控可以解耦为3个通道:

  • 水平通道
  • 高度通道
  • 偏航通道

这3个通道可以分别控制,可以理解为通道之间相互不会影响。水平通道可以控制四旋翼的水平位置、水平速度、水平姿态角;高度通道可以控制垂直高度、垂直速度、垂直加速度;偏航通道可以控制偏航角度、偏航角速度、偏航角加速度。

本文例子程序中的 x,y 是水平通道的指令,控制四旋翼水平方向的飞行;z 是高度通道指令,控制四旋翼的高度。本文例子程序中没有偏航通道指令,默认的偏航是 0,也就是四旋翼自身不会水平旋转,其朝向始终朝向前方。

1. 控制命令

首先是一个高度控制的API

client.moveToZAsync(-3, 1).join()   # 高度控制

参数分别是高度和速度。-3是因为Airsim中使用的NED坐标系,右手系。

1.1 moveToPositionAsync(x, y, z, velocity)
client.moveToPositionAsync(5, 0, -3, 1).join()

水平控制APImoveToPositionAsync(x, y, z, velocity),xyz是全局坐标系,v是速度。表示的是以v的速度飞到(x,y,z)这个点。

函数的定义:

def moveToPositionAsync(
         self,
         x,          # 位置坐标(北东地坐标系)
         y,
         z,
         velocity,   # 速度
         timeout_sec=3e38,  # 如果没有响应,超时时间
         drivetrain=DrivetrainType.MaxDegreeOfFreedom,
         yaw_mode=YawMode(), # 设置飞行朝向模式和yaw角控制模式
         lookahead=-1,
         adaptive_lookahead=1,  # 置路径飞行的时候的yaw角控制模式
         vehicle_name="",
     )

x, y, z, velocity 这四个参数是必须要设置的量,指示四旋翼以多大的速度飞往哪个坐标点。后面的几个参数都有其默认值,不用设置也可以。

lookahead 和 adaptive_lookahead 这两个参数是设置当四旋翼飞轨迹的时候的朝向。

drivetrain 和 yaw_mode 这两个参数的组合可以设置四旋翼的偏航角控制模式。

1.2 moveByVelocityZAsync(vx, vy, z, duration)
client.moveByVelocityZAsync(vx, vy, z, duration).join()

速度控制函数,让四旋翼在z的高度,以vx, vy的速度,飞行duration秒。.join()是程序在这里等待任务执行完成。

函数定义:

def moveByVelocityZAsync(
         self,
         vx,
         vy,
         z,
         duration,
         drivetrain=DrivetrainType.MaxDegreeOfFreedom,
         yaw_mode=YawMode(),
         vehicle_name="",
     )
  • vx:全局坐标系下x轴方向上的速度
  • vy:全局坐标系下y轴方向上的速度
  • z:全局坐标系下的高度
  • duration:持续的时间,单位:秒
  • drivetrain, yaw_mode:用来设置偏航控制

还有另一个与之很相近的函数:

client.moveByVelocityAsync(vx, vy, vz, duration, drivetrain = DrivetrainType.MaxDegreeOfFreedom, yaw_mode = YawMode(), vehicle_name = '')

这里面vz表示的是z轴方向的速度

四旋翼是一个非线性系统,给一个速度指令,它是不可能瞬时达到的,而且这个速度指令与当前的速度之差越大,到达这个速度指令的调节时间就越长。

1.3 固定视角设置
  • F 按键:FPV
  • B 按键:跟随/FlyWithMe
  • \ 按键:地面观察者/GroundObserver
  • / 按键:弹性机臂跟随/SpringArmChase
  • M 按键:手动/Manual
1.4 偏航角模式

drivetrain 参数可以设置为两个量:

  • airsim.DrivetrainType.ForwardOnly: 始终朝向速度方向
  • airsim.DrivetrainType.MaxDegreeOfFreedom:手动设置yaw角度

yaw_mode 必须设置为 YawMode() 类型的变量,这个结构体类型包含两个属性:

  • YawMode().is_rate:True - 设置角速度;False - 设置角度
  • YawMode().yaw_or_rate:可以是任意浮点数

情况1 (不允许):

drivetrain = airsim.DrivetrainType.ForwardOnly
 yaw_mode = airsim.YawMode(True, 0)
 client.moveToPositionAsync(x, y, z, velocity, drivetrain=drivetrain, yaw_mode=yaw_mode).join()

drivetrain = airsim.DrivetrainType.ForwardOnly 时,四旋翼始终朝向其飞行的方向,这时 yaw_mode 不允许设置为 YawMode().is_rate = True。因为前面的参数要求四旋翼朝向运动方向,而 yaw_mode 要求四旋翼以一定的角速度旋转,这是矛盾的。

情况2:

drivetrain = airsim.DrivetrainType.ForwardOnly
 yaw_mode = airsim.YawMode(False, 90)
 client.moveToPositionAsync(x, y, z, velocity, drivetrain=drivetrain, yaw_mode=yaw_mode).join()

这种情况下,四旋翼的朝向始终与前进方向相差90度,也就是四旋翼始终向左侧方向运动。例如:当四旋翼在绕着一个圆心转圈时,其朝向始终指向圆心(这种飞行状态的代码在下一篇文章中给出)。这里的90度可以任意设置。

情况3:

drivetrain = airsim.DrivetrainType.MaxDegreeOfFreedom
yaw_mode = airsim.YawMode(False, 0)
client.moveToPositionAsync(x, y, z, velocity, drivetrain=drivetrain, yaw_mode=yaw_mode).join()

这种情况下,不管速度方向是什么,四旋翼的yaw角始终等于0, 也就是其朝向始终指向正北方向。如果是90度,则始终指向正东方向,而-90度,则始终指向正西方向。

情况4:

drivetrain = airsim.DrivetrainType.MaxDegreeOfFreedom
 yaw_mode = airsim.YawMode(True, 10)
 client.moveToPositionAsync(x, y, z, velocity, drivetrain=drivetrain, yaw_mode=yaw_mode).join()

这种情况下,四旋翼不管速度方向是什么,yaw角以10度/秒的速度旋转。

简而言之,当drivetrain设置为始终朝向速度方向时,yaw_mode就不可以设置角速度。

1.5 航路点飞行API

AirSim 提供的轨迹跟踪 API 是基于位置控制的,所以严格意义上并不能算是轨迹跟踪,而应该称之为连续航路点飞行。无人机会依次飞过多个航路点,形成特定的飞行轨迹,其调用格式如下。

# 航路点轨迹飞行控制
 client.moveOnPathAsync(path, velocity, 
                   drivetrain = DrivetrainType.MaxDegreeOfFreedom, 
                   yaw_mode = YawMode(),
                   lookahead = -1, adaptive_lookahead = 1, 
                   vehicle_name = '')

参数说明:

  • path (list[Vector3r]):多个航路点的3维坐标(全局 NED 坐标系,原点是无人机的初始位置);
  • velocity (float):无人机的飞行速度大小;
  • lookahead, adaptive_lookahead:设置路径跟踪算法的参数。

参数 path 包含了多个航路点的全局位置坐标, 也就是说无人机要飞过 path 中包含的每一个坐标点(也就是航路点)。将 path 中的航路点依次连接起来,就会组成一条路径,无人机依次飞过航路点,就像是沿着特定路径飞行一样,形成路径跟踪的效果。

“moveOnPathAsync” 中使用的算法是 “Carrot Chasing Algorithm”,这是一个非常经典的路径跟踪算法,其中需要设置 “lookahead” 参数,这个参数的意义是设置在路径上向前看的距离。“lookahead” 设置的越大,在路径拐弯的时候,无人机就越提前转弯;如果 “lookahead” 参数设置的过小,则可能会出现超调,无人机会飞跃航路点,然后才拐弯。

2. 获取无人机状态

无人机位置读取时使用的是全局坐标系,这里的全局坐标系定义是北东地(NED),全局坐标系的原点是无人机的初始位置。

2.1 获取估计状态
  • 这个状态是由传感器估计的状态,并不是无人机状态的真值。
  • AirSim默认的无人机底层飞控 simple_flight 并不支持状态估计,所以如果是simple_flight 飞控,此函数得到的状态与真值相同。
  • 使用PX4 飞控可以获取估计的状态
state = client.getMultirotorState(vehicle_name = '')

其中无人机的状态变量 state 包含如下:

class MultirotorState(MsgpackMixin):
     collision = CollisionInfo()                 # 碰撞信息
     kinematics_estimated = KinematicsState()    # 状态信息
     gps_location = GeoPoint()                   # GPS 信息
     timestamp = np.uint64(0)                    # 时间戳
     landed_state = LandedState.Landed           # 是否是降落状态
     rc_data = RCData()                          # 遥控器数据
     ready = False
     ready_message = ""
     can_arm = False

读取方式如下:

state_multirotor.collision              # 碰撞信息
 state_multirotor.kinematics_estimated   # 运动信息 
 state_multirotor.gps_location           # GPS经纬度信息
 state_multirotor.timestamp              # 时间戳 仿真开始后的时间 单位为纳秒
 state_multirotor.landed_state           # 降落信息  0为在地面,1为在空中
 state_multirotor.rc_data                # 遥控器信息

碰撞信息的定义:

class CollisionInfo(MsgpackMixin):
     has_collided = False
     normal = Vector3r()
     impact_point = Vector3r()
     position = Vector3r()
     penetration_depth = 0.0
     time_stamp = 0.0
     object_name = ""
     object_id = -1

状态信息的定义:

class KinematicsState(MsgpackMixin):
     position = Vector3r()               # 位置
     orientation = Quaternionr()         # 姿态角
     linear_velocity = Vector3r()        # 速度
     angular_velocity = Vector3r()       # 机体角速率
     linear_acceleration = Vector3r()    # 加速度
     angular_acceleration = Vector3r()   # 机体角加速度

读取方式:

# 无人机运动信息的估计值的6个属性
 state_multirotor.kinematics_estimated.position               # 位置信息估计值
 state_multirotor.kinematics_estimated.linear_velocity        # 速度信息估计值
 state_multirotor.kinematics_estimated.linear_acceleration    # 加速度信息估计值
 state_multirotor.kinematics_estimated.orientation            # 姿态信息估计值
 state_multirotor.kinematics_estimated.angular_velocity       # 姿态角速率信息估计值
 state_multirotor.kinematics_estimated.angular_acceleration   # 姿态角加速度信息估计值

GPS 信息包含:

class GeoPoint(MsgpackMixin):
     latitude = 0.0
     longitude = 0.0
     altitude = 0.0
2.2 获取状态真值
kinematics_state_groundtruth = client.simGetGroundTruthKinematics(vehicle_name = '')

其中返回值 kinematic_state_groundtruth包含6个属性:

# state_groundtruth 的6个属性
kinematic_state_groundtruth.position               # 位置信息
kinematic_state_groundtruth.linear_velocity	   # 速度信息
kinematic_state_groundtruth.linear_acceleration    # 加速度信息
kinematic_state_groundtruth.orientation	           # 姿态信息
kinematic_state_groundtruth.angular_velocity       # 姿态角速率信息
kinematic_state_groundtruth.angular_acceleration   # 姿态角加速度信息

以上6个属性中,除了 orientation 其他每个都包含了 x_valy_valz_val三个属性,分别代表x,y,z3个方向的值。例如位置真值的读取如下:

# 无人机全局位置坐标真值
x = kinematic_state_groundtruth.position.x_val            # 全局坐标系下,x轴方向的坐标
y = kinematic_state_groundtruth.position.y_val            # 全局坐标系下,y轴方向的坐标
z = kinematic_state_groundtruth.position.z_val            # 全局坐标系下,z轴方向的坐标

同理,速度、加速度、姿态角速度、姿态角加速度真值的读取如下:

# 无人机全局速度真值
vx = kinematic_state_groundtruth.linear_velocity.x_val      # 无人机 x 轴方向 (正北) 的速度大小真值
vy = kinematic_state_groundtruth.linear_velocity.y_val      # 无人机 y 轴方向 (正东) 的速度大小真值
vz = kinematic_state_groundtruth.linear_velocity.z_val      # 无人机 z 轴方向 (垂直向下) 的速度大小真值
# 无人机全局加速度真值
ax = kinematic_state_groundtruth.linear_acceleration.x_val  # 无人机 x 轴方向 (正北) 的加速度大小真值
ay = kinematic_state_groundtruth.linear_acceleration.y_val  # 无人机 y 轴方向 (正东) 的加速度大小真值
az = kinematic_state_groundtruth.linear_acceleration.z_val  # 无人机 z 轴方向 (垂直向下) 的加速度大小真值
# 机体角速率
kinematic_state_groundtruth.angular_velocity.x_val        # 机体俯仰角速率
kinematic_state_groundtruth.angular_velocity.y_val        # 机体滚转角速率
kinematic_state_groundtruth.angular_velocity.z_val        # 机体偏航角速率
# 机体角加速度
kinematic_state_groundtruth.angular_acceleration.x_val    # 机体俯仰角加速度
kinematic_state_groundtruth.angular_acceleration.y_val    # 机体滚转角加速度
kinematic_state_groundtruth.angular_acceleration.z_val    # 机体偏航角加速度

而对于姿态的读取,姿态信息是用四元数表示的,而AirSim同时也提供了四元数转换为欧拉角的接口:

# 无人机姿态真值的四元数表示
kinematic_state_groundtruth.orientation.x_val
kinematic_state_groundtruth.orientation.y_val
kinematic_state_groundtruth.orientation.z_val
kinematic_state_groundtruth.orientation.w_val
# 四元数转换为欧拉角,单位rad
(pitch, roll, yaw) = airsim.to_eularian_angles(kinematic_state_groundtruth.orientation)

3 图像API

3.1 调用simGetImage接口

simGetImage接口的调用方式如下:

# 一次获取一张图片
 response = client.simGetImage(camera_name, image_type, vehicle_name='')

参数说明:

  • camera_name (string):想要拍摄照片的相机ID;
  • image_type (自定义类型 ImageType):想要拍摄的照片的种类;
  • response (bytes):字节形式存储的图像。

其中 camera_nameimage_type 是必须要设置的输入参数,用于指定使用无人机上的哪个相机和拍摄的图像类型,vehicle_name指定使用哪一架无人机。

返回值response是 bytes格式,是PNG格式图像的内容,其中不包含如相机等其他信息。所以使用simGetImage接口仅能拍摄PNG格式的图像。

3.2 调用simGetImages接口

simGetImages接口可以以一种更灵活的方式拍摄图像,它可以一次获取多张不同类型的图片,同时也包含了拍摄信息和图片信息。此接口的调用格式如下:

# 同时获取多张图片(包括拍摄信息和图片信息)
 responses = client.simGetImages(requests, vehicle_name= '')

参数说明:

  • requests (list[ImageRequest]):对图片的需求描述的列表;
  • responses (list[ImageResponse]):返回的图片列表。

参数 ImageRequest是AirSim的自定义类型,需要设置的参数包括:

# ImageRequest 初始化
 airsim.ImageRequest(camera_name, image_type, pixels_as_float=False, compress=True)

参数说明:

  • pixels_as_float (bool):设置图片是否以浮点型格式保存;
  • compress (bool):设置图片是否压缩。

针对3种图片形式,需要设置的参数总结如下表所示。

图像类型

compress

pixels_as_float

适合保存的图片类型

PNG 格式

True

False

彩色图、分割图、表面法线图、红外图

Array 格式

False

False

彩色图、分割图、表面法线图、红外图

浮点型格式

False

True

深度图

函数的返回值 responses 是list[ImageResponse]格式,ImageResponse是AirSim的自定义类型,其中包含的属性有:

# ImageResponse 包含的属性
 ImageResponse.image_data_uint8   # (list[uint8])int型存储的图片数据
 ImageResponse.image_data_float   # (list[float])浮点型存储的图片数据
 ImageResponse.camera_position    # (Vector3r)拍摄图片时相机的全局位置
 ImageResponse.camera_orientation # (Quaternionr)拍摄图片时相机的姿态信息
 ImageResponse.time_stamp         # (uint64)时间戳
 ImageResponse.message            # (string)传输的信息
 ImageResponse.pixels_as_float    # (bool)是否以浮点型保存图片数据
 ImageResponse.compress           # (bool)是否压缩图片
 ImageResponse.width              # (int)图片宽的像素个数
 ImageResponse.height             # (int)图片高的像素个数 
 ImageResponse.image_type         # (ImageType)图片的类型

其中,图片的原始数据保存在image_data_uint8image_data_float中。如果拍摄的是 PNG或 Array格式的图片,则图片数据以bytes格式保存在 ImageResponse.image_data_uint8 中,如果拍摄的是浮点型格式的图片,则数据保存在 ImageResponse.image_data_float 中。

可以看到返回的ImageResponse中包含了很多其他信息,例如:拍摄照片时的相机位置和姿态、时间戳、图片格式、图片分辨率、图片类型等,这对于后续的图片处理有很大的帮助。所以使用simGetImages接口可以获得更加丰富的信息。

3.3 图像数据保存为文件

使用APIs获取到的图像是保存在变量中的,程序运行结束后就会释放掉,为了将图像保留下来,需要将图像保存到文件中。不同格式的图像保存的方式不同,保存的目标文件格式也不同,本节分别介绍保存图像的步骤,并举例说明。

3.3.1 保存PNG格式的图像

使用 simGetImage 接口可以直接得到以PNG协议保存的 bytes 格式图像数据。使用 simGetImages 接口通过手动设置输入参数,也可以得到以PNG协议保存的 bytes 格式图像数据。彩色图、分割图、红外图、表面法线图都支持获取PNG格式的图像。

PNG格式的图像保存比较简单,因为使用APIs读取到的图像就已经是以PNG协议形式存储的 bytes 格式,只需要将获取到的数据按照二进制格式写入文件中即可,同时文件后缀名要保存成.png格式。下面通过代码举例说明如何保存。

**举例1:**使用simGetImage获取PNG格式的彩色图,并保存成 .png 格式的图片文件:

# 获取PNG格式的彩色图,并保存到文件中
 client = airsim.MultirotorClient()
 response = client.simGetImage("front_center", airsim.ImageType.Scene)
 f = open('scene.png', 'wb')
 f.write(response)
 f.close()

其中 f = open('1.png', 'wb')scene.png 表示文件路径和命名,如果没有此文件则创建文件; w 表示文件可写入;b表示以二进制 (bytes)格式读写文件。其中的responsebytes 格式,保存的是以PNG协议的图像内容。最后的 f.close() 必须执行,不然会出现错误。

**举例2:**使用 simGetImages 获取PNG格式的分割图,并保存成 .png 格式的图片文件。

client = airsim.MultirotorClient()
 responses = client.simGetImages([
     airsim.ImageRequest(0, airsim.ImageType.Segmentation, pixels_as_float=False, compress=True)])
 f = open('seg.png', 'wb')
 f.write(responses[0].image_data_uint8)
 f.close()

**举例3:**使用 simGetImages 同时获取PNG格式的红外图和表面法线图,并保存成2个.png格式的图片文件。

client = airsim.MultirotorClient()
 responses = client.simGetImages([
     airsim.ImageRequest(0, airsim.ImageType.Infrared, pixels_as_float=False, compress=True),
     airsim.ImageRequest(0, airsim.ImageType.SurfaceNormals, pixels_as_float=False, compress=True)])
 # 保存红外图
 f = open('infrared.png', 'wb')
 f.write(responses[0].image_data_uint8)
 f.close()
 # 保存表面法线图
 f = open('surface.png', 'wb')
 f.write(responses[1].image_data_uint8)
 f.close()
3.3.2 保存 Array格式的图像

Array 格式的图像数据是图像最原始的保存形式,其意义很直观,大部分的图像处理如目标检测都需要 Array 格式。numpy库中提供了 array 相关的操作,所以在程序开头要导入 numpy 模块,为了方便,一般习惯性写成import numpy as np

使用 OpenCV库中的 imwrite可以将 Array 格式的图像保存成任意格式的图像文件。所以使用python程序需要导入 OpenCV 库,需要在程序开头写上 import cv2

实例代码如下。

import airsim
 import numpy as np
 import cv2
 
 client = airsim.MultirotorClient()
 # 读取图像数据,array格式
 responses = client.simGetImages([
     airsim.ImageRequest(0, airsim.ImageType.Scene, pixels_as_float=False, compress=False)])
 # 将bytes格式转换为 array格式
 img_1d = np.frombuffer(responses[0].image_data_uint8, dtype=np.uint8)
 img_bgr = img_1d.reshape(responses[0].height, responses[0].width, 3)
 # 保存为图片文件
 cv2.imwrite('scene.png', img_bgr)  # 保存为.png格式的图像文件
 cv2.imwrite('scene.jpg', img_bgr)  # 保存为.jpg格式的图像文件
 cv2.imwrite('scene.tif', img_bgr)  # 保存为.tif格式的图像文件
 cv2.imwrite('scene.bmp', img_bgr)  # 保存为.bmp格式的图像文件

其中在使用 simGetImages接口读取图像时,将 compress 设置为 False,即可得到 array格式的图像数据。此数据以 bytes 格式保存在 responses[i].image_data_uint8中,所以首先需要将其转换为 Array 格式的数据。

转换过程分为2步,使用 np.frombuffer 可以将bytes 格式的数据转换为1维的array格式,再使用reshape 复原成 height\times width \times 3 维的array格式的图像数据。使用 AirSim APIs 接口读到的 Array 格式图像数据的三个通道顺序是 BGR(蓝绿红),所以我们在程序中将读到的 Array 格式的图像数据命名为 img_bgr,便于后续的处理。

使用 OpenCV库中的 cv2.cvtColor()接口可以进行BGR Array和 RGB Array的相互转换。具体代码如下:

# 使用OpenCv库,进行BGR Array和 RGB Array的相互转换
 img_rgb = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2RGB)  # BGR到RGB的转换
 img_bgr = cv2.cvtColor(img_rgb, cv2.COLOR_RGB2BGR)  # BGR到RGB的转换

将 array格式的图像数据保存到图像文件中,需要用到cv2.imwrite()接口,此接口的调用格式如下:

import cv2
 cv2.imwrite(img_path, img_src, [params])

参数说明:

  • img_path (string):图片文件的路径名,必须包含扩展名;
  • img_src (np.array):array格式的图像数据,通道顺序为 BGR;
  • [params]:保存图像的参数设定。

cv2.imwrite()接口可以保存不同格式的图像文件,如上面的例子所示,可以保存.png.jpg.tif.bmp等格式的图像文件。其中 [params]可以设置一些压缩率、图片质量等参数,其中.jpg格式的图片是有损压缩的图片。例如设置.jpg图像文件的质量为 10%,则代码为:

cv2.imwrite('scene_lowQuality.jpg', img_bgr, [cv2.IMWRITE_JPEG_QUALITY, 10])
3.3.3 PNG 和 Array 格式图像数据的相互转换

使用opencv 中的encode 和 decode可以转换不同格式的图像数据。从PNG格式的图像数据转换为 Array格式叫做解码 (decode),反过来叫做编码 (encode)。这其实很好理解,因为 Array 格式的图像数据是最原始的图像数据,而 PNG 格式是根据协议压缩后的数据,所以叫做编码。OpenCV库中提供了相应的接口,可以很方便的相互转换。

下面的代码举例说明了如何将 PNG 格式的图像数据转换为 Array 格式的图像数据。

# PNG 格式的图像数据转换为 Array 格式的图像数据
 # 使用AirSim API 读取PNG格式的图像数据
 responses = client.simGetImages([
     airsim.ImageRequest(0, airsim.ImageType.Scene, 
                         pixels_as_float=False, compress=True)])
 # 1. 将PNG格式的图像数据,从bytes格式转换为 numpy.ndarray 格式
 img_png = np.frombuffer(responses[0].image_data_uint8, np.uint8)
 # 2. 转换为 Array 格式的图像数据,BGR顺序
 img_bgr = cv2.imdecode(img_png, cv2.IMREAD_COLOR)
 # 最终可以将Array格式的图像数据保存为 .png 格式的文件
 cv2.imwrite('scene.png', img_bgr)

同样的,使用cv2.imencode()可以将 Array 格式的图像数据转换为 PNG 格式,下面的例子比较详细地说明了如何将 Array 格式的图像数据转换为 PNG 格式,并保存为 .png 格式的图片文件。

# 将 Array 格式的图像数据转换为 PNG 格式, 并保存为 `.png` 格式的图片文件
 # 使用AirSim API 读取Array格式的图像数据
 responses = client.simGetImages([
     airsim.ImageRequest(0, airsim.ImageType.Scene, 
                         pixels_as_float=False, compress=False)])
 
 img_1d = np.frombuffer(responses[0].image_data_uint8, np.uint8)
 img_bgr = img_1d.reshape(responses[0].height, responses[1].width, 3)
 # 将 Array 格式的图像数据转换为 PNG 格式
 img_png = cv2.imencode('.png', img_bgr)[1].tobytes()
 # 将 PNG 格式的图像数据写入文件,即可保存为 `.png`格式的图片文件
 f = open('1.png', 'wb')
 f.write(img_png)
 f.close()

另外 cv2.imencode() 还将 Array 格式的图像数据编码为其他的图像数据格式,详细内容请参考OpenCV 官网,下面的代码是转换为 JPG 格式。

# 转换为 JPG 格式的图像数据
 img_jpg = cv2.imencode('.jpg', img_bgr)[1].tobytes()
3.3.4 灰度图的保存

有时候我们需要使用和保存灰度图,例如在深度图的处理中,通常为了观察方便会将原始深度图进行一些处理,例如将纯白色表示距离为100米或更远,纯黑色表示距离为0米。

因为灰度图仅有一个通道,所以 Array 格式灰度图的大小和维度为 height \times width。使用OpenCV库中的接口可以方便地将彩色图转换为灰度图。

# BGR顺序的Array彩色图转换为灰度图
 img_gray = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2GRAY)
 # RGB顺序的Array彩色图转换为灰度图
 img_gray = cv2.cvtColor(img_rgb, cv2.COLOR_RBG2GRAY)
 # 灰度图保存为图片文件
 cv2.imwrite('scene_gray.png', img_gray)
(img_png)
 f.close()

另外 cv2.imencode() 还将 Array 格式的图像数据编码为其他的图像数据格式,详细内容请参考OpenCV 官网,下面的代码是转换为 JPG 格式。

# 转换为 JPG 格式的图像数据
 img_jpg = cv2.imencode('.jpg', img_bgr)[1].tobytes()
3.3.4 灰度图的保存

有时候我们需要使用和保存灰度图,例如在深度图的处理中,通常为了观察方便会将原始深度图进行一些处理,例如将纯白色表示距离为100米或更远,纯黑色表示距离为0米。

因为灰度图仅有一个通道,所以 Array 格式灰度图的大小和维度为 height \times width。使用OpenCV库中的接口可以方便地将彩色图转换为灰度图。

# BGR顺序的Array彩色图转换为灰度图
 img_gray = cv2.cvtColor(img_bgr, cv2.COLOR_BGR2GRAY)
 # RGB顺序的Array彩色图转换为灰度图
 img_gray = cv2.cvtColor(img_rgb, cv2.COLOR_RBG2GRAY)
 # 灰度图保存为图片文件
 cv2.imwrite('scene_gray.png', img_gray)