在gazebo中我们可以将模型包放置于.gazebo/models路径下,在gazebo中可以直接将这些模型包随意拖出来用,非常的方便,本篇将以mini_gazebo中的地图模型文件创建为例,教大家如何去创建一个简易模型包。地图包地址具体可看该地址:[gazebo仿真,讯飞智慧餐厅,tianbot_mini二轮差速小车]
1.[从SolidWorks导出URDF]
2.在Blender中对模型进行贴图
3、 urdf转sdf
打开racetrack_v2/urdf,路径,可以发现有urdf代码文件,使用命令:
gz sdf -p racetrack_v2.urdf > racetrack_v2.sdf
gz sdf -p racetrack_v2.urdf > racetrack_v2.sdf
gz sdf -p racetrack_v2.urdf > racetrack_v2.sdf
gz sdf -p racetrack_v2.urdf > racetrack_v2.sdf
复制
可以发现sdf文件生成了

4 、创建模型包
创建一个新的文件夹,命名为任意名字,我这里命名为racetrack_V2,将上一步生成的sdf文件,以及urdf功能包中的meshes文件夹复制进去,再创建一个model.config的文件,如图:

model.config里面定义了需要加载的sdf文件名,以及可注明作者信息等,代码如下:
<?xml version="1.0"?>
<model>
<name>racetrack_v2</name>
<version>1.0</version>
<sdf version="1.6">racetrack_v2.sdf</sdf>
<author>
<name>Yuxing Zhang</name>
<email>1632122398@qq.com</email>
</author>
<description>
A racetrack world
</description>
</model>
<?xml version="1.0"?> <model> <name>racetrack_v2</name> <version>1.0</version> <sdf version="1.6">racetrack_v2.sdf</sdf> <author> <name>Yuxing Zhang</name> <email>1632122398@qq.com</email> </author> <description> A racetrack world </description> </model>
<?xml version="1.0"?> <model> <name>racetrack_v2</name> <version>1.0</version> <sdf version="1.6">racetrack_v2.sdf</sdf> <author> <name>Yuxing Zhang</name> <email>1632122398@qq.com</email> </author> <description> A racetrack world </description> </model>
<?xml version="1.0"?> <model> <name>racetrack_v2</name> <version>1.0</version> <sdf version="1.6">racetrack_v2.sdf</sdf> <author> <name>Yuxing Zhang</name> <email>1632122398@qq.com</email> </author> <description> A racetrack world </description> </model>
此时一个简易的模型包就创建好了,将该模型包复制到.gazebo/models路径下,打开gazebo即可找到该地图模型了,将点击该模型将其加载进gazebo中:

5、 另存为world
gazebo中拖出的模型,想在下一次打开时还能保持自己设置的状态,则需要将其保存为world文件,并用launch文件将其打开。点击file-->save world as,可将world暂时保存在r任意功能包world文件夹中。配置launch文件,命名为racetrack_gazebo.launch:
<?xml version="1.0"?>
<launch>
<!-- 设置launch文件的参数 -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<arg name="x_pos" default="0"/>
<arg name="y_pos" default="0"/>
<arg name="z_pos" default="0.01"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find racetrack_v2)/world/racetrack.world" />
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
</launch>
<?xml version="1.0"?> <launch> <!-- 设置launch文件的参数 --> <arg name="paused" default="false"/> <arg name="use_sim_time" default="true"/> <arg name="gui" default="true"/> <arg name="headless" default="false"/> <arg name="debug" default="false"/> <arg name="x_pos" default="0"/> <arg name="y_pos" default="0"/> <arg name="z_pos" default="0.01"/> <!-- 运行gazebo仿真环境 --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find racetrack_v2)/world/racetrack.world" /> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)"/> <arg name="use_sim_time" value="$(arg use_sim_time)"/> <arg name="headless" value="$(arg headless)"/> </include> </launch>
<?xml version="1.0"?> <launch> <!-- 设置launch文件的参数 --> <arg name="paused" default="false"/> <arg name="use_sim_time" default="true"/> <arg name="gui" default="true"/> <arg name="headless" default="false"/> <arg name="debug" default="false"/> <arg name="x_pos" default="0"/> <arg name="y_pos" default="0"/> <arg name="z_pos" default="0.01"/> <!-- 运行gazebo仿真环境 --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find racetrack_v2)/world/racetrack.world" /> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)"/> <arg name="use_sim_time" value="$(arg use_sim_time)"/> <arg name="headless" value="$(arg headless)"/> </include> </launch>
<?xml version="1.0"?> <launch> <!-- 设置launch文件的参数 --> <arg name="paused" default="false"/> <arg name="use_sim_time" default="true"/> <arg name="gui" default="true"/> <arg name="headless" default="false"/> <arg name="debug" default="false"/> <arg name="x_pos" default="0"/> <arg name="y_pos" default="0"/> <arg name="z_pos" default="0.01"/> <!-- 运行gazebo仿真环境 --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find racetrack_v2)/world/racetrack.world" /> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)"/> <arg name="use_sim_time" value="$(arg use_sim_time)"/> <arg name="headless" value="$(arg headless)"/> </include> </launch>
启动racetrack_gazebo.launch文件:
roslaunch racetrack_v2 racetracke_gazebo.launch
roslaunch racetrack_v2 racetracke_gazebo.launch
roslaunch racetrack_v2 racetracke_gazebo.launch
roslaunch racetrack_v2 racetracke_gazebo.launch
可以发现,gazebo环境配置与上一次配置的一样:

6 加载world时报错
有时gazebo加载world文件时会报错:

[urdf_spawner-4] process has died [pid 17273, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -urdf -model libot -param robot_description -x 0 -y 0 -z 0 -R 0 -P 0 -Y 0 __name:=urdf_spawner__log:=/home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4.log]. log file: /home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4*.log
[urdf_spawner-4] process has died [pid 17273, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -urdf -model libot -param robot_description -x 0 -y 0 -z 0 -R 0 -P 0 -Y 0 __name:=urdf_spawner__log:=/home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4.log]. log file: /home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4*.log
[urdf_spawner-4] process has died [pid 17273, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -urdf -model libot -param robot_description -x 0 -y 0 -z 0 -R 0 -P 0 -Y 0 __name:=urdf_spawner__log:=/home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4.log]. log file: /home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4*.log
[urdf_spawner-4] process has died [pid 17273, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -urdf -model libot -param robot_description -x 0 -y 0 -z 0 -R 0 -P 0 -Y 0 __name:=urdf_spawner__log:=/home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4.log]. log file: /home/zyx/.ros/log/cdf87ba4-c6d7-11ec-a7b9-d0abd53c1adb/urdf_spawner-4*.log
可以修改world文件中标签,将两个参数都改为0,下一次加载便不会再报该错误:

参考文献
评论(0)
您还未登录,请登录后发表或查看评论