由于ros2中不能像ros1中一样使用soildworks导出urdf文件直接打开,所以之前使用的下面的方法没有用了
https://blog.csdn.net/weixin_42454034/article/details/106545710
只有使用其它方法了。
首先在soildworks中建模:
导出为.stl格式。
之后通过meshlab将其转化为 gazebo可以使用的.dae格式
meshlab下载
打开软件,通过File -> Import Mesh 导入soildworks导出的文件。
随后在 File -> Export Mesh As 导出为.dae格式。
导出的路径中不能含有中文,不然会导出错误。
在ubuntu中按照gazebo的格式创建文件夹.
其中meshes文件夹中存放.dae文件.
model.config文件如下: 按照TurtleBot3的写法改的.
<?xml version="1.0"?>
<model>
<name>pipe_cool</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>Taehun Lim(Darby)</name>
<email>thlim@robotis.com</email>
</author>
<description>
World of TurtleBot3 with ROS symbol
</description>
</model>
model.sdf 文件如下:
<sdf version='1.7'>
<model name='pipe_cool'>
<static>true</static>
<link name='base_footprint'>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>2165.2</mass>
<inertia>
<ixx>0</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0</iyy>
<iyz>0</iyz>
<izz>0</izz>
</inertia>
</inertial>
<collision name='base_footprint_fixed_joint_lump__base_link_collision'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://pipe_cool/meshes/pipe_cool.dae</uri>
</mesh>
</geometry>
</collision>
<visual name='base_footprint_fixed_joint_lump__base_link_visual'>
<pose>0 0 0 1.57 -0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>model://pipe_cool/meshes/pipe_cool.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>
其中两个uri标签中放的是dae文件位置,mass和inertia标签现在是随便填的.
随后在bashrc文件中加入文件路径.要根据自己的目录改.
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:~/Desktop/gis_ws/src/gis_gazebo/models
source ~/.bashrc后
运行 gazebo
在insert中出现了新添加的路径,路径下有模型名字,将其拖入gazebo
为了方便在ros2中使用,将其另存为.world文件
通过urdf文件编写一个简单的小车模型后,在ros2中加载
# #!/usr/bin/env python3
import os
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import ThisLaunchFileDir
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from launch.actions import ExecuteProcess
from launch.substitutions import LaunchConfiguration
def generate_launch_description():
gazebo_dir = os.path.join(get_package_share_directory('gazebo_ros'),'launch')
world = os.path.join(get_package_share_directory('gis_gazebo'), 'worlds', 'pipe_cool.world')
urdf = os.path.join(
get_package_share_directory('gis_gazebo'),
'urdf','gis_car.urdf')
with open(urdf, 'r') as infp:
robot_desc = infp.read()
model_path = os.path.join(
get_package_share_directory('gis_gazebo'),
'urdf','test.sdf')
use_sim_time = LaunchConfiguration('use_sim_time', default=True)
return LaunchDescription([
#退出gazebo时gzserver经常关不掉,所以打开gazebo前先关掉gzserver
ExecuteProcess(
cmd=['killall','-q', 'gzserver'],
output='screen'),
ExecuteProcess(
cmd=['killall','-q', 'gzclient'],
output='screen'),
IncludeLaunchDescription(
PythonLaunchDescriptionSource([gazebo_dir, '/gzserver.launch.py']),
launch_arguments={
'world': world
}.items(),
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource([gazebo_dir ,'/gzclient.launch.py'])),
#使用-file 打开sdf文件
#使用-database需要先将模型路径添加到GAZEBO_MODEL_PATH 'export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:model_path' 而且模型需要参照gazebo中的标准写法才能成功加载
#使用-topic订阅机器人话题 话题由robot_state_publisher发布 其打开的是urdf文件
Node(package='gazebo_ros', node_executable='spawn_entity.py',
arguments=[
'-x','0.0',
'-y','0.0',
'-z','2.0',
'-Y','0.0', #yaw
'-entity', 'car', #gazebo中机器命名
# '-database', 'cardboard_box',
# '-file',model_path,
'-topic','robot_description',
],
output='screen'),
Node(
package='robot_state_publisher',
node_executable='robot_state_publisher',
node_name='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': use_sim_time},
{'publish_frequency':100.0},
{'robot_description':robot_desc},
],
# arguments=[urdf]
),
])
最终效果: