天天看點

ros2foxy中gazebo11中導入soildworks中模型

由于ros2中不能像ros1中一樣使用soildworks導出urdf檔案直接打開,是以之前使用的下面的方法沒有用了

https://blog.csdn.net/weixin_42454034/article/details/106545710
           

隻有使用其它方法了。

首先在soildworks中模組化:

ros2foxy中gazebo11中導入soildworks中模型

導出為.stl格式。

之後通過meshlab将其轉化為 gazebo可以使用的.dae格式

meshlab下載下傳

打開軟體,通過File -> Import Mesh 導入soildworks導出的檔案。

ros2foxy中gazebo11中導入soildworks中模型

随後在 File -> Export Mesh As 導出為.dae格式。

導出的路徑中不能含有中文,不然會導出錯誤。

在ubuntu中按照gazebo的格式建立檔案夾.

ros2foxy中gazebo11中導入soildworks中模型

其中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>[email protected]</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

ros2foxy中gazebo11中導入soildworks中模型

為了友善在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]
            ),

    ])

           

最終效果:

ros2foxy中gazebo11中導入soildworks中模型

繼續閱讀