本文主要从两个方向介绍,一种是基于射影变换的月球表面环境构建;另一种是基于高度图的三维仿真环境构建,目前两种方式都已经实现。本文将引导读者从获取数据集开始完成对月球表面的三维环境构建仿真。
构建仿真文件
在构建三维表面环境的配置中,需要加入一系列的模型文件、配置文件以及发布文件,整个过程对于ROS新手而言是非常晦涩的,我反正一开始就弄糊涂了,不知道文件与文件之间的层级关系。在这里首先给一个大概的概念。ROS的发布文件.launch
是相当于可执行文件一样的存在,即是可以直接运行的程序 ,类比于Linux系统下的.sh
文件。发布文件中将包含一系列的配置文件以及配置参数,相当于.sh
中的一系列参数与函数,因此配置文件相当于不完整的.sh
文件,而模型文件只存在于配置文件的调用中,通常不通过发布文件直接调用它。
获取原始数据
无论是三维仿真环境抑或是二维的射影变换仿真,都需要获取较高精度的月球表面遥感图像,目前能够获取到的、开源且较为完整的月球表面数据集是NASA的月球表面数字高程图 和月球表面去除阴影的地形照片 ,分别从对应的路径下载即可,推荐使用IDM 或者XDM 等并发下载器下载,源文件较大,单点下载极慢。
对于去除阴影的遥感地形图,官网上提供有该地形照片的描述文件 和PDS格式说明文件 。查阅描述文件可知,该.tif
文件共有以下组成成分:
项目
数值
文件总字节数
11,325,604,841
文件标签字节数
984,041
文件行数
61,440
文件列数
184,320
文件数据类型
8位无符号整数
因此,理论上该文件可以直接使用PIL
或者matplotlib
等库文件读取,但是由于文件过于巨大,读取存放在内存中极占资源,导致运行速度变慢,且这样做是没有必要的。可以采取流式读取的方式完成数据提取,这里,以960 行作为一个单元,逐单元读取,然后拆分为192个960 × 960 960\times 960 960 × 960 的小单元块,共计64 × 192 = 12288 64\times 192=12288 64 × 192 = 12288 个小单元块,完成原始文件的提取。提供拆分该图像的python脚本如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 import numpy as npimport matplotlib.pyplot as pltimport tqdmimport osif __name__ == "__main__" : path = "/path/to/your/Lunar_LRO_LOLAKaguya_Shade_60N60S_512ppd.tif" output_dir = ( "/path/to/your/output" ) LABEL_BYTES = 984003 BYTES_PER_PIXEL = 1 LINES = 61440 LINE_SAMPLES = 184320 base_batch = 960 num_batches = LINES // base_batch num_samples = LINE_SAMPLES // base_batch print ( f"The basic batch of DEM is {base_batch} x{base_batch} . Each line contains {num_samples} batches. There are totally {num_batches*num_samples} basic batches." ) with open (path, "rb" ) as f: line = f.read(LABEL_BYTES) for row in tqdm.tqdm(range (num_batches)): data = f.read(LINE_SAMPLES * BYTES_PER_PIXEL * base_batch) data_array = np.frombuffer(data, dtype=np.uint8).reshape( base_batch, LINE_SAMPLES )
同理,如果要处理深度图,同样获取对应的描述文件和格式文件,查阅得知除了单位像素的数据位数不同以外,其余与地形图都完全相同。只需要将位深BYTES_PER_PIXEL
取为2,并将数据类型转换为np.uint16
,即可完成深度图的逐块读取。
取得地形图后,可以直接使用matplotlib
完成对单元块的输出,如下所示:
1 2 3 4 5 6 7 8 9 10 plt.imsave( os.path.join( output_dir, "textures" , f"{row} " , f"txr_{row} _{col} _{base_batch} .png" , ), img_array, cmap="gray" , )
这样,就可以完成对地形图的输出,然后可以在gazebo环境中编辑需要加载的地形照片,以完成仿真环境的搭建,得到的子地形图如下所示:
与该图对应位置的深度图如下所示:
深度图转三维模型
本部分内容仅针对需要构建三维仿真环境的需求而言,如不需要构建三维仿真环境,则完全可以跳过本部分内容。
深度图,尤其是二维的深度图可以直接通过三维点的面片拟合完成模型构建,numpy-stl
库提供了简单的三维模型操作指令,可用于构建简单的stl
模型。请提前确保numpy-stl
库已经安装到位。在前文提到的原始960 × 960 960\times 960 960 × 960 单位深度图上,增加以下部分功能代码:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 def make3d (img_array, filename, base_batch=960 , scale_factor=59 ): ''' convert the depth map into a 3D model :param img_array: depth map ndarray :param filename: output filename :param base_batch: the basic size of depth map :param scale_factor: scale factor ''' from stl import mesh x = np.arange(0 , base_batch, 1 ) y = np.arange(0 , base_batch, 1 ) X, Y = np.meshgrid(x, y) Z = img_array / scale_factor num_vertices = base_batch * base_batch num_faces = 2 * (base_batch - 1 ) * (base_batch - 1 ) vertices = np.zeros((num_vertices, 3 )) vertices[:, 0 ] = X.flatten() vertices[:, 1 ] = Y.flatten() vertices[:, 2 ] = Z.flatten() faces = [] for i in range (base_batch - 1 ): for j in range (base_batch - 1 ): faces.append( [ i * base_batch + j, (i + 1 ) * base_batch + j + 1 , (i + 1 ) * base_batch + j, ] ) faces.append( [ i * base_batch + j, i * base_batch + j + 1 , (i + 1 ) * base_batch + j + 1 , ] ) surface_mesh = mesh.Mesh(np.zeros(num_faces, dtype=mesh.Mesh.dtype)) for i, f in enumerate (faces): for j in range (3 ): surface_mesh.vectors[i][j] = vertices[f[j], :] surface_mesh.save(filename)
其中注释部分的内容是用于生成带有底座的三维模型,以方便进一步使用(例如三维打印等),不带注释将生成不带有底座的曲面片(厚度为零),所得的stl
文件更小,方便仿真。其中的scale_factor
参数是根据深度图或者地形图单个像素长度对应的真实长度的比例尺,为了保证得到的三维模型是原始模型的倍缩模型,必须在宽高和深度三个方向上都保持相同的比例关系。这里,深度图和地形图的的比例尺是1 pixel : 59 m
,因此scale_factor
取59。使用渲染软件Meshlab
可视化得到的模型如下所示:
在处理原始深度图像单元块的主程序 中加入以下代码:
1 2 3 4 5 6 7 8 9 10 11 make3d( img_array, os.path.join( output_dir, "models" , f"{row} " , f"model_{row} _{col} _{base_batch} .stl" , ), base_batch=base_batch, scale_factor=59 , )
即可生成对应单元块的三维模型,这样就完成了对深度图的三维模型构建。
另一个值得注意的点是,stl
模型由一系列三角形面元拼接而成,其文件数据结构是存储的各点深度以及各点构建的三角面元顺序关系。当三角面元的顶点顺序为顺时针时,面元被视为正面,反之被视为背面。而背面的模型在某些渲染引擎中将是不可见的(例如gazebo
),如下图所示:
图中左图是正常渲染的月球表面三维模型,而右图是错误渲染结果,可见错误渲染结果可视化失败,且仿真传感器也无法获取正常的光照或者纹理等信息。
所有 的三角面元的顶点顺序都必须是相同的,否则模型将无法正确显示。
构建三维世界
同样地,如果不需要完成三维仿真环境构建,只需要跳过本部分即可。如果需要将构建得到的三维模型加入至gazebo
仿真环境中,首先需要在模型文件夹Tools/sitl_gazebo/models
内新建模型,例如,将该模型命名为moon_surface_3d
,其中文件的结构如下所示:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 moon_surface_3d ├── materials │ └── textures │ ├── txr_0_0_960.png │ ├── txr_0_1_960.png │ ├── txr_1_0_960.png | └── ... ├── meshes │ ├── 0_0_960.stl │ ├── 0_1_960.stl │ ├── 1_0_960.stl | └── ... ├── model.config └── moon.sdf
其中的textures
子文件夹存放的是用于贴图的纹理文件,就是深度图对应位置处的去阴影地形图,该文件可以用于获取更加真实的视觉模型体验。打开新建的model.sdf
文件,加入的内容如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 <?xml version="1.0" ?> <sdf version ="1.4" > <model name ="moon_surface_3d" > <static > true</static > <link name ="link" > <collision name ="collision_0_0" > <geometry > <mesh > <uri > model://moon_surface_3d/meshes/0_0_960.stl</uri > <scale > 0.1 0.1 0.1</scale > </mesh > </geometry > </collision > <visual name ="visual_0_0" > <geometry > <mesh > <uri > model://moon_surface_3d/meshes/0_0_960.stl</uri > <scale > 0.1 0.1 0.1</scale > </mesh > </geometry > <material > <ambient > 0.5 0.5 0.5 1</ambient > <diffuse > 0.5 0.5 0.5 1</diffuse > <script > <uri > model://moon_surface_3d/materials/textures/txr_0_0_960.png</uri > <name > MoonSurface/Diffuse_0_0</name > </script > </material > </visual > <collision name ="collision_0_1" > <geometry > <pose > 100 0 0 0 0 0</pose > <mesh > <uri > model://moon_surface_3d/meshes/0_1_960.stl</uri > <scale > 0.1 0.1 0.1</scale > </mesh > </geometry > </collision > <visual name ="visual_0_1" > <pose > 100 0 0 0 0 0</pose > <geometry > <mesh > <uri > model://moon_surface_3d/meshes/0_1_960.stl</uri > <scale > 0.1 0.1 0.1</scale > </mesh > </geometry > <material > <ambient > 0.5 0.5 0.5 1</ambient > <diffuse > 0.5 0.5 0.5 1</diffuse > <script > <uri > model://moon_surface_3d/materials/textures/txr_0_1_960.png</uri > <name > MoonSurface/Diffuse_0_1</name > </script > </material > </visual > </link > </model > </sdf >
在model.config
文件中加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 <?xml version="1.0" ?> <model > <name > moon_surface_3d</name > <version > 1.0</version > <sdf > moon.sdf</sdf > <author > <name > Your name</name > </author > <description > A simple moon surface model </description > </model >
然后按照文件目录要求放入对应的纹理文件和模型文件,在Tools/sitl_gazebo/worlds
文件夹中新建一个moon_surface_3d.world
文件,加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 <?xml version="1.0" ?> <sdf version ="1.5" > <world name ="default" > <include > <uri > model://sun</uri > </include > <include > <name > moon part 0 67</name > <uri > model://moon_surface_3d</uri > <pose > 0 0 0 0 0 0</pose > </include > <physics name ='default_physics' default ='0' type ='ode' > <gravity > 0 0 -9.8066</gravity > <ode > <solver > <type > quick</type > <iters > 10</iters > <sor > 1.3</sor > <use_dynamic_moi_rescaling > 0</use_dynamic_moi_rescaling > </solver > <constraints > <cfm > 0</cfm > <erp > 0.2</erp > <contact_max_correcting_vel > 100</contact_max_correcting_vel > <contact_surface_layer > 0.001</contact_surface_layer > </constraints > </ode > <max_step_size > 0.002</max_step_size > <real_time_factor > 1</real_time_factor > <real_time_update_rate > 500</real_time_update_rate > <magnetic_field > 6.0e-6 2.3e-5 -4.2e-5</magnetic_field > </physics > <light name ="moon_surface_3d_light" type ="directional" > <cast_shadows > false</cast_shadows > <pose > 0 0 100 0 0.8 0.2</pose > <diffuse > 0.8 0.8 0.8 1</diffuse > <specular > 0.2 0.2 0.2 1</specular > <attenuation > <range > 1000</range > <constant > 0.9</constant > <linear > 0.01</linear > <quadratic > 0.001</quadratic > </attenuation > <direction > -0.5 0.1 -0.9</direction > </light > </world > </sdf >
这里的各项参数可以根据实际情况调整,注意,模型光照选项<cast_shadows>
被关闭是因为,gazebo
自带的阴影效果实在是惨不忍睹,还不如不要,因此将其显式关闭。如需要添加更多的单位面元,请在上述配置文件中按相同的形式复制粘贴并修改名字即可。至此,三维仿真世界的环境构建工作就完成了。
构建二维世界
二维模型的加载与三维模型基本一致,不同之处在于,二维模型不需要加载stl
文件,因此其模型文件夹结构如下所示:
1 2 3 4 5 6 7 8 9 10 moon_surface_2d ├── materials │ ├── scripts │ │ └── moon_surface.material │ └── textures │ ├── txr_0_0_960.png │ ├── txr_0_1_960.png │ └── ... ├── model.config └── moon_surface.sdf
有两种方式可以实现对二维地形图像的加载,一种是通过二维地表贴图,即先加臷一个ground_plane
模型,然后在该模型上加贴图,另一种则是直接加载二维地形图像,然后设置对二维地形图像的碰撞信息。这里选取的是第二种方式。首先,在moon_surface.sdf
文件中写入以下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 <?xml version="1.0" ?> <sdf version ="1.4" > <model name ="moon_surface" > <static > true</static > <link name ="link" > <collision name ="collision_0_0" > <pose > 0 0 0 0 0 0</pose > <geometry > <plane > <normal > 0 0 1</normal > <size > 96 96</size > </plane > </geometry > </collision > <visual name ="visual_0_0" > <pose > 0 0 0 0 0 0</pose > <geometry > <plane > <normal > 0 0 1</normal > <size > 96 96</size > </plane > </geometry > <material > <script > <uri > model://moon_surface/materials/textures/</uri > <uri > model://moon_surface/materials/scripts/</uri > <name > MoonSurface/Diffuse_0_0</name > </script > </material > </visual > <collision name ="collision_0_1" > <pose > 95.9 0 0 0 0 0</pose > <geometry > <plane > <normal > 0 0 1</normal > <size > 96 96</size > </plane > </geometry > </collision > <visual name ="visual_0_1" > <pose > 95.9 0 0 0 0 0</pose > <geometry > <plane > <normal > 0 0 1</normal > <size > 96 96</size > </plane > </geometry > <material > <script > <uri > model://moon_surface/materials/textures/</uri > <uri > model://moon_surface/materials/scripts/</uri > <name > MoonSurface/Diffuse_0_1</name > </script > </material > </visual > </link > </model > </sdf >
在model.config
文件中加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 <?xml version="1.0" ?> <model > <name > Ground Plane</name > <version > 1.0</version > <sdf version ="1.6" > moon_surface.sdf</sdf > <author > <name > your model name</name > <email > abcd@buaa.edu.cn</email > </author > <description > A simple moon surface for crater simulation. </description > </model >
注意model.config文件中的<name>
标签中的内容必须与sdf文件中的<model>
标签中的<name>
标签中的内容一致,否则模型无法加载。在materials/scripts
文件夹中新建一个moon_surface.material
文件,加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 material MoonSurface/Diffuse_0_0 { technique { pass { ambient 1.0 1.0 1.0 1.0 diffuse 1.0 1.0 1.0 1.0 specular 0.0 0.0 0.0 1.0 1.0 texture_unit { texture txr_0_0_960.png filtering trilinear } } } } material MoonSurface/Diffuse_0_1 { technique { pass { ambient 1.0 1.0 1.0 1.0 diffuse 1.0 1.0 1.0 1.0 specular 0.0 0.0 0.0 1.0 1.0 texture_unit { texture txr_0_1_960.png filtering trilinear } } } }
同样,本文件中的material
字段的内容也需要与sdf文件中的<material>
标签中的<name>
标签中的内容一致,否则模型无法加载。如需要添加由更多面片组成更大范围的仿真环境,请在两个文件中按相同的形式ctrl C ctrl V
并修改文件名和标签名即可。至此,二维仿真世界的环境构建工作就完成了。
构建世界模型
本步骤需要在Tools/sitl_gazebo/worlds
文件中增加一个moon_surface.world
文件,加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 <?xml version="1.0" ?> <sdf version ="1.5" > <world name ="default" > <include > <uri > model://sun</uri > </include > <include > <name > moon</name > <uri > model://moon_surface</uri > <pose > 0 0 0 0 0 0</pose > </include > <physics name ='default_physics' default ='0' type ='ode' > <gravity > 0 0 -9.8066</gravity > <ode > <solver > <type > quick</type > <iters > 10</iters > <sor > 1.3</sor > <use_dynamic_moi_rescaling > 0</use_dynamic_moi_rescaling > </solver > <constraints > <cfm > 0</cfm > <erp > 0.2</erp > <contact_max_correcting_vel > 100</contact_max_correcting_vel > <contact_surface_layer > 0.001</contact_surface_layer > </constraints > </ode > <max_step_size > 0.002</max_step_size > <real_time_factor > 1</real_time_factor > <real_time_update_rate > 500</real_time_update_rate > <magnetic_field > 6.0e-6 2.3e-5 -4.2e-5</magnetic_field > </physics > <light name ="moon_surface_light" type ="directional" > <pose > 0 0 100 0 0.8 0.2</pose > <diffuse > 0.8 0.8 0.8 1</diffuse > <specular > 0.2 0.2 0.2 1</specular > <attenuation > <range > 1000</range > <constant > 0.9</constant > <linear > 0.01</linear > <quadratic > 0.001</quadratic > </attenuation > <direction > -0.5 0.1 -0.9</direction > </light > </world > </sdf >
此时的世界模型就可以通过本文件修改其全局的物理参数,如模型的大小、重力加速度或者摩擦系数等,不需要在模型文件中逐个设置。
构建发布文件
最后,需要在Tools/sitl_gazebo/launch
文件夹中新建一个moon_surface.launch
文件,本文件将含有包括世界模型、加入的无人机模型(包括上面固连的传感器模型)以及其他任何自定义的模型。在该文件中加入如下内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 <?xml version="1.0" ?> <launch > <arg name ="x" default ="5" /> <arg name ="y" default ="5" /> <arg name ="z" default ="20" /> <arg name ="R" default ="0" /> <arg name ="P" default ="0" /> <arg name ="Y" default ="0" /> <arg name ="my_model" default ="iris_evt_cam" /> <arg name ="est" default ="ekf2" /> <arg name ="vehicle" default ="iris" /> <arg name ="world" default ="$(find mavlink_sitl_gazebo)/worlds/moon.world" /> <arg name ="sdf" default ="$(find mavlink_sitl_gazebo)/models/$(arg my_model)/$(arg my_model).sdf" /> <arg name ="gui" default ="true" /> <arg name ="debug" default ="false" /> <arg name ="verbose" default ="false" /> <arg name ="paused" default ="false" /> <arg name ="respawn_gazebo" default ="false" /> <arg name ="fcu_url" default ="udp://:14540@localhost:14557" /> <arg name ="respawn_mavros" default ="false" /> <arg name ="interactive" default ="true" /> <include file ="$(find px4)/launch/posix_sitl.launch" > <arg name ="x" value ="$(arg x)" /> <arg name ="y" value ="$(arg y)" /> <arg name ="z" value ="$(arg z)" /> <arg name ="R" value ="$(arg R)" /> <arg name ="P" value ="$(arg P)" /> <arg name ="Y" value ="$(arg Y)" /> <arg name ="world" value ="$(arg world)" /> <arg name ="vehicle" value ="$(arg vehicle)" /> <arg name ="sdf" value ="$(arg sdf)" /> <arg name ="gui" value ="$(arg gui)" /> <arg name ="interactive" value ="$(arg interactive)" /> <arg name ="debug" value ="$(arg debug)" /> <arg name ="verbose" value ="$(arg verbose)" /> <arg name ="paused" value ="$(arg paused)" /> <arg name ="respawn_gazebo" value ="$(arg respawn_gazebo)" /> </include > <include file ="$(find mavros)/launch/px4.launch" > <arg name ="gcs_url" value ="" /> <arg name ="fcu_url" value ="$(arg fcu_url)" /> <arg name ="respawn_mavros" value ="$(arg respawn_mavros)" /> </include > </launch >
至此,所有的文件配置都已经准备就绪。
运行仿真环境
至此激动人心的时刻终于来了,首先请确保所有文件都保存完毕,打开容器的终端,确保自己的catkin_ws
工作目录的环境变量和PX4_Autopilot
的环境变量都已经激活,然后运行以下命令:
1 roslaunch px4 moon_mavros_posix_sitl.launch
此时将可以看到仿真环境正常加载,如下图所示:
然后另起一个终端,运行以下命令:
此时将会打开QGroundControl
软件,可以通过该软件对无人机进行控制,如下图所示:
然后再另起一个终端,运行以下命令:
1 roslaunch dvs_renderer davis_mono.launch
刚打开时可能该用户界面什么也显示不了,这是因为无人机尚未起飞 ,传感器仍处于关机模式 ,此时需要使用QG控制无人机使其飞行,然后界面将显示可视化后的事件图像,如下所示:
至此,可视化采集和仿真环境的搭建工作就全部到位了,下一章节中将介绍使用ROS的订阅器和推送器接口完成自动化的数据采集。