ソースを参照

修改gazebo中显示相关配置文件,现在可以在gazebo fortress中正常加载机器人启动

corvin_zhang 1 週間 前
コミット
24409314d5

+ 114 - 24
guguji_ros2_ws/src/guguji_ros2/launch/gazebo.launch.py

@@ -1,18 +1,65 @@
 import os
+import shlex
 
 from ament_index_python.packages import get_package_share_directory
 from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
+from launch.actions import (
+    DeclareLaunchArgument,
+    IncludeLaunchDescription,
+    OpaqueFunction,
+    SetEnvironmentVariable,
+    SetLaunchConfiguration,
+    TimerAction,
+)
 from launch.conditions import IfCondition
 from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
+from launch.substitutions import (
+    EnvironmentVariable,
+    LaunchConfiguration,
+    PathJoinSubstitution,
+)
 from launch_ros.actions import Node
 from launch_ros.substitutions import FindPackageShare
 
 
+def _configure_gz_args(context, *args, **kwargs):
+    """根据 launch 参数拼接 Fortress 的启动命令参数。"""
+    world = LaunchConfiguration('world').perform(context)
+    gui = LaunchConfiguration('gui').perform(context).lower() == 'true'
+    pause = LaunchConfiguration('pause').perform(context).lower() == 'true'
+    verbose = LaunchConfiguration('verbose').perform(context).strip().lower()
+
+    gz_args = []
+
+    # -r 表示启动后立即运行;如果 pause:=true,则故意不加 -r。
+    if not pause:
+        gz_args.append('-r')
+
+    # Fortress 下 -s 表示仅启动服务端,不弹 GUI。
+    if not gui:
+        gz_args.append('-s')
+
+    # 兼容两种传参方式:
+    # 1. verbose:=true  -> 使用较详细的 4 级日志
+    # 2. verbose:=3     -> 直接指定日志等级
+    if verbose not in ('', 'false', '0', 'no', 'off'):
+        verbose_level = '4' if verbose in ('true', 'yes', 'on') else verbose
+        gz_args.extend(['-v', verbose_level])
+
+    gz_args.append(world)
+
+    return [
+        SetLaunchConfiguration(
+            'gz_args_resolved',
+            ' '.join(shlex.quote(arg) for arg in gz_args)
+        )
+    ]
+
+
 def generate_launch_description():
     package_name = 'guguji_ros2'
     package_share = get_package_share_directory(package_name)
+    package_share_parent = os.path.dirname(package_share)
     urdf_path = os.path.join(package_share, 'urdf', 'guguji.urdf')
     default_world = os.path.join(package_share, 'worlds', 'empty.world')
 
@@ -22,6 +69,7 @@ def generate_launch_description():
         robot_description = urdf_file.read()
 
     world = LaunchConfiguration('world')
+    world_name = LaunchConfiguration('world_name')
     use_sim_time = LaunchConfiguration('use_sim_time')
     gui = LaunchConfiguration('gui')
     pause = LaunchConfiguration('pause')
@@ -34,28 +82,78 @@ def generate_launch_description():
     pitch = LaunchConfiguration('pitch')
     yaw = LaunchConfiguration('yaw')
 
+    # Gazebo Fortress 通过资源搜索路径查找 package:// 包内网格文件。
+    # 对于安装后的包,加入 share 和 share 的父目录后,
+    # 就能正确解析 package://guguji_ros2/meshes/... 这类路径。
+    resource_path_actions = [
+        SetEnvironmentVariable(
+            name='GZ_SIM_RESOURCE_PATH',
+            value=[
+                package_share_parent,
+                os.pathsep,
+                package_share,
+                os.pathsep,
+                EnvironmentVariable('GZ_SIM_RESOURCE_PATH', default_value=''),
+            ],
+        ),
+        SetEnvironmentVariable(
+            name='IGN_GAZEBO_RESOURCE_PATH',
+            value=[
+                package_share_parent,
+                os.pathsep,
+                package_share,
+                os.pathsep,
+                EnvironmentVariable('IGN_GAZEBO_RESOURCE_PATH', default_value=''),
+            ],
+        ),
+    ]
+
     gazebo_launch = IncludeLaunchDescription(
         PythonLaunchDescriptionSource(
             PathJoinSubstitution([
-                FindPackageShare('gazebo_ros'),
+                FindPackageShare('ros_gz_sim'),
                 'launch',
-                'gazebo.launch.py',
+                'gz_sim.launch.py',
             ])
         ),
         launch_arguments={
-            'world': world,
-            'gui': gui,
-            'pause': pause,
-            'verbose': verbose,
+            'gz_args': LaunchConfiguration('gz_args_resolved'),
+            'on_exit_shutdown': 'true',
         }.items(),
     )
 
+    spawn_entity = Node(
+        package='ros_gz_sim',
+        executable='create',
+        name='spawn_guguji',
+        output='screen',
+        arguments=[
+            '-world', world_name,
+            '-name', 'guguji',
+            # 直接从 /robot_description 取模型字符串,
+            # 后续如果你把 URDF 改成 xacro,也不需要改这里的加载方式。
+            '-topic', '/robot_description',
+            '-x', x_pose,
+            '-y', y_pose,
+            '-z', z_pose,
+            '-R', roll,
+            '-P', pitch,
+            '-Y', yaw,
+            '-allow_renaming', 'true',
+        ],
+    )
+
     return LaunchDescription([
         DeclareLaunchArgument(
             'world',
             default_value=default_world,
             description='Gazebo 启动时使用的 world 文件路径'
         ),
+        DeclareLaunchArgument(
+            'world_name',
+            default_value='default',
+            description='在 world 文件中用于生成实体的 world 名称'
+        ),
         DeclareLaunchArgument(
             'use_sim_time',
             default_value='true',
@@ -74,7 +172,7 @@ def generate_launch_description():
         DeclareLaunchArgument(
             'verbose',
             default_value='false',
-            description='是否输出 Gazebo 详细日志'
+            description='Gazebo 日志等级;可填 false/true 或数值 0~4'
         ),
         DeclareLaunchArgument(
             'publish_joint_state',
@@ -111,6 +209,9 @@ def generate_launch_description():
             default_value='0.0',
             description='模型生成时的 Yaw 角'
         ),
+        # 先根据 launch 参数拼出 Fortress 的 gz_args,再去 include 官方启动文件。
+        OpaqueFunction(function=_configure_gz_args),
+        *resource_path_actions,
         gazebo_launch,
         Node(
             package='robot_state_publisher',
@@ -133,20 +234,9 @@ def generate_launch_description():
                 'use_sim_time': use_sim_time,
             }],
         ),
-        Node(
-            package='gazebo_ros',
-            executable='spawn_entity.py',
-            name='spawn_guguji',
-            output='screen',
-            arguments=[
-                '-entity', 'guguji',
-                '-file', urdf_path,
-                '-x', x_pose,
-                '-y', y_pose,
-                '-z', z_pose,
-                '-R', roll,
-                '-P', pitch,
-                '-Y', yaw,
-            ],
+        # 稍微等待 Gazebo 世界初始化完成后再创建模型,可减少 Fortress 启动初期的竞争问题。
+        TimerAction(
+            period=2.0,
+            actions=[spawn_entity],
         ),
     ])

+ 4 - 1
guguji_ros2_ws/src/guguji_ros2/package.xml

@@ -8,18 +8,21 @@
   <buildtool_depend>ament_cmake</buildtool_depend>
 
   <exec_depend>ament_index_python</exec_depend>
-  <exec_depend>gazebo_ros</exec_depend>
   <exec_depend>joint_state_publisher</exec_depend>
   <exec_depend>joint_state_publisher_gui</exec_depend>
   <exec_depend>launch</exec_depend>
   <exec_depend>launch_ros</exec_depend>
   <exec_depend>robot_state_publisher</exec_depend>
   <exec_depend>ros2launch</exec_depend>
+  <exec_depend>ros_gz_sim</exec_depend>
   <exec_depend>rviz2</exec_depend>
+  <exec_depend>sdformat_urdf</exec_depend>
   <exec_depend>urdf</exec_depend>
   <exec_depend>xacro</exec_depend>
 
   <export>
     <build_type>ament_cmake</build_type>
+    <!-- 让 Gazebo Fortress 在启动时可以自动把本包资源目录加入搜索路径。 -->
+    <gazebo_ros gazebo_model_path="${prefix}/../" gazebo_media_path="${prefix}/../"/>
   </export>
 </package>

+ 50 - 7
guguji_ros2_ws/src/guguji_ros2/worlds/empty.world

@@ -1,11 +1,54 @@
 <?xml version="1.0" ?>
-<sdf version="1.6">
+<!-- 使用自包含的 SDF world,避免 Fortress 环境中找不到 sun / ground_plane 模型资源。 -->
+<sdf version="1.8">
   <world name="default">
-    <include>
-      <uri>model://ground_plane</uri>
-    </include>
-    <include>
-      <uri>model://sun</uri>
-    </include>
+    <gravity>0 0 -9.8</gravity>
+
+    <scene>
+      <ambient>0.4 0.4 0.4 1.0</ambient>
+      <background>0.8 0.8 0.8 1.0</background>
+      <shadows>true</shadows>
+    </scene>
+
+    <light name="sun" type="directional">
+      <cast_shadows>true</cast_shadows>
+      <pose>0 0 10 0 0 0</pose>
+      <diffuse>0.8 0.8 0.8 1.0</diffuse>
+      <specular>0.2 0.2 0.2 1.0</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>
+
+    <model name="ground_plane">
+      <static>true</static>
+      <link name="link">
+        <collision name="collision">
+          <geometry>
+            <plane>
+              <normal>0 0 1</normal>
+              <size>100 100</size>
+            </plane>
+          </geometry>
+        </collision>
+        <visual name="visual">
+          <geometry>
+            <plane>
+              <normal>0 0 1</normal>
+              <size>100 100</size>
+            </plane>
+          </geometry>
+          <material>
+            <ambient>0.85 0.85 0.85 1.0</ambient>
+            <diffuse>0.85 0.85 0.85 1.0</diffuse>
+            <specular>0.1 0.1 0.1 1.0</specular>
+          </material>
+        </visual>
+      </link>
+    </model>
   </world>
 </sdf>