数字孪生之Gazebo导入自建场景(.obj文件)做仿真训练
在现实场景中采集图像、雷达、imu数据,然后用重建算法重建出meshes文件,加载到仿真器中做仿真训练,实现数字孪生(digital twin)。
Do not blindly trust anything I say, try to make your own judgement.
目录
2.1 blender逐个导入.obj文件并导出.dae文件
1. 准备工作
在现实场景中采集图像、雷达、imu数据,然后用重建算法重建出meshes文件,加载到仿真器中做仿真训练,实现数字孪生。由于自建场景不便公开,本文不展示操作效果图。
本文以新建一个example.world场景为例,所需的环境如下:
- ubuntu
- ROS
- gazebo仿真器
- 重建后的.obj文件(重建算法这里不做介绍)
- blender软件:sudo apt-get install blender
首先确认启动blender和gazebo的时候是否自动使用了GPU(用nvidia-smi查看),如果不用GPU,则加载场景会非常慢,因此建议使用GPU。若未自动使用GPU,则说明nvidia driver版本不合适,需要重装driver。
2. 配置步骤
2.1 blender逐个导入.obj文件并导出为.dae文件
重建场景的mesh文件格式有很多,如.obj,.stl,.dae等,其中gazebo需要加载的场景文件格式是.dae,而我重建的mesh文件格式是.obj,因此需要先用blender将.obj格式转为.dae文件,其他格式的mesh也都可以用blender转成.dae格式。
首先有一些重建后的多个文件夹如下图所示,相当于对一个自建场景做了分块,每个文件夹里包含一个.obj文件及对应的纹理(贴图)。
每个文件夹里有如下文件,其中Tile_+000_+000.obj就是主要的obj文件,.mtl文件是纹理文件,对应的贴图是.jpg文件。
在blender中的点击File-Import-Wavefront(.obj)选择加载每个文件夹里的.obj文件,它会把同级路径下的bbox.obj,.mtl文件,jpg文件都自动加载进来。并且新加载的obj的位置会自动与已加载的obj对齐。导入后的mesh不会直接显示纹理色彩,需要点击菜单栏中的texture paint才会显示出纹理。
全部obj文件加载完后,点击File-Export-Collada(.dae)导出.dae文件,就会把obj文件全部合并成一个.dae文件,并且把所有.jpeg文件跟.dae文件一起保存下来。
(注意,gazebo加载.dae文件大小极限一般在1.5GB,超过1.5GB之后加载场景会非常卡,难以做仿真,一般小于1GB的自建场景文件比较合适。如果场景文件过大,则需要在blender中使用场景压缩技术,降低mesh片数,这里不做介绍。)
2.2 用.dae文件创建可以加载到gazebo的world
首先创建一个world文件夹命名为example,文件夹下包含三个元素:meshes文件夹、model.sdf、model.config。
- meshes文件夹里保存的就是blender里导出的.dae文件及自带的所有纹理文件.material,需要将上一步导出的.dae文件和.jpeg文件复制到meshes路径下,如下图所示:
- model.sdf是world文件的表述文件,定义了基本属性如碰撞、纹理等。其中sdf version="1.5"可以随意指定,只是给自己看的;static设成true可以把静态场景文件固定;model name和link name改成想要加载到gazebo中的场景名称;两个<mesh> </mesh>中间的<uri>要改成.dae文件的路径;pose表示的是文件的初始位姿(x,y,z,yaw,pitch,yaw);friction摩擦力系数也很重要。
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="example">
<!-- if set static = False, the scene model will be moveable and drop.-->
<static> true </static>
<!-- Give the base link a unique name -->
<link name="example">
<!-- The visual is mostly a copy of the collision -->
<pose>0 0 0 0 0 0</pose>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://example/meshes/example.dae</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<!-- mu: vertical friction coefficient -->
<mu>100</mu>
<!-- mu2: horizontal friction coefficient -->
<mu2>50</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<!-- Offset the visual by have the base's height. We are not rotating
mesh since symmetrical -->
<geometry>
<mesh>
<uri>model://example/meshes/example.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>
- model.config文件如下:name:example表示world的名称,model.sdf加载的就是同级目录下的sdf文件。
<?xml version="1.0"?>
<model>
<name>example</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>Optional: YOUR NAME</name>
<email>Optional: YOUR EMAIL</email>
</author>
<description>
example.
</description>
</model>
- 配置完以上三个元素后,由于gazebo默认读取的world路径是.gazebo/models/,因此还要给创建好的example文件创建软连接,链接到.gazebo/models路径下,这样gazebo才能识别到该场景:
cd .gazebo/models/
ln -s path_to_example(e.g., ~/example/)
2.3 gazebo导出仿真所需的.world文件
打开gazebo,在左侧的Insert一栏中可以找到新建的场景example,点击该场景会将其加载进来。
加载到gazebo之后,在菜单栏点击File-Save World As,然后命名导出的文件后缀为.world,gazebo就会自动生成example.world文件,该文件是用来指定启动仿真时要加载的场景。
.world文件内容示例如下:
<sdf version='1.6'>
<world name='default'>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose frame=''>0 0 10 0 -0 0</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>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<physics name='default_physics' default='0' type='ode'>
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<wind/>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<model name='example'>
<static>1</static>
<link name='example'>
<pose frame=''>0 0 0 0 -0 0</pose>
<collision name='collision'>
<geometry>
<mesh>
<uri>model://example/meshes/example.dae</uri>
</mesh>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<contact>
<ode/>
</contact>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://example/meshes/example.dae</uri>
</mesh>
</geometry>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<pose frame=''>0.513522 2.28029 0 0 -0 0</pose>
</model>
<state world_name='default'>
<sim_time>0</sim_time>
<real_time>0</real_time>
<wall_time>0</wall_time>
<iterations>0</iterations>
<model name='example'>
<pose frame=''>0.513522 2.28029 0 0 -0 0</pose>
<scale>1 1 1</scale>
<link name='example'>
<pose frame=''>0.513522 2.28029 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<light name='sun'>
<pose frame=''>0 0 10 0 -0 0</pose>
</light>
</state>
<gui fullscreen='0'>
<camera name='user_camera'>
<pose frame=''>4.6003 -4.3514 1.82182 0 0.275643 2.35619</pose>
<view_controller>orbit</view_controller>
<projection_type>perspective</projection_type>
</camera>
</gui>
</world>
</sdf>
2.4 编写launch文件以启动.world文件
用launch文件的方式启动仿真加载场景,这里只展示launch文件中启动仿真场景的代码。以turtlebot3仿真为例(roslaunch turtlebot3_gazebo turtlebot3_world.launch),其中example.world是我们自己生成的仿真场景文件。
<?xml version="1.0"?>
<launch>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find turtlebot3_gazebo)/worlds/example.world"/>
<arg name="gui" default="true"/>
<arg name="use_sim_time" value="true" />
</include>
</launch>
3. 其他问题
- 启动launch文件时报错waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertise:
解决方案: 同时开多个gazebo会报这个错,一次只能开启一个gazebo。 - 启动gazebo launch仿真时报错:spawn service failed:
解决方案:1)将.world文件中的sim_time值改成0;
2)机器人模型出生点原点存在碰撞,无法加载进去。 - 小车在场景中没重力,可以在空中行驶:
解决方案:1)不是场景的重力问题,是小车xacro中的关节控制器配置有问题;
2)也可能是太卡了导致real time factor非常小,小车下落还没显示出来。 - 键盘控制不了gazebo中的小车:
解决方案:要先安装ros对应版本的gazebo-ros的通信软件包sudo apt install ros-melodic-gazebo-ros-pkgs ros-melodic-gazebo-msgs ros-melodic-gazebo-plugins ros-melodic-gazebo-ros-control
4. Reference
更多推荐
所有评论(0)