程序项目代做,有需求私信(小程序、网站、爬虫、电路板设计、驱动、应用程序开发、毕设疑难问题处理等)

龙芯2k0300 - 走马观碑组Gazebo仿真环境搭建

一、概述

1.1 为什么要仿真

搭建Gazebo仿真环境对于智能车比赛(特别是涉及视觉巡线、强化学习等算法开发)来说,不是可选项,而是最优解。以下是需要搭建仿真环境的核心理由,以及它能解决的实际问题。

1.1.1 硬件不足

问题:你现在没有久久派、摄像头、电机等硬件,但需要写程序、验证算法。

Gazebo的作用:

  • 提供虚拟的小车模型(带摄像头、激光雷达等传感器);
  • 提供虚拟的赛道环境(可以自定义颜色、形状、材质);
  • 程序写完后,直接在Gazebo里运行,效果等同于在真车上测试;

结果:硬件还没到,你的巡线算法已经跑通了。硬件一到,只需换底层驱动即可。

1.1.2 缩短调试周期
调试场景 真车调试 Gazebo仿真
修改PID参数 烧录→上电→跑一圈→观察→再烧录(5-10分钟/次) 改代码→保存→重启仿真(10秒/次)
小车撞墙 可能损坏硬件(电机、舵机、车架) 重置位置,继续调试
跑完一整圈 需要清场、充电、防止撞人 无限制运行,无人值守
测试极端情况 可能翻车、失控 完全安全

结论:仿真环境让的调试效率提升30-50倍。

1.1.3 提供可复现的测试环境

问题:真车测试时,光线变化、地面摩擦力、电池电量都会影响结果,今天跑通的代码明天可能就失效。

Gazebo的优势:

  • 每次启动都是完全相同的环境(相同的光照、相同的摩擦力、相同的传感器噪声);
  • 可以精确控制变量:比如只改变线条颜色,其他不变;
  • 算法性能变化只由代码改动引起,排除了环境干扰;

这对于调参、对比算法优劣至关重要。

1.1.4 支持强化学习训练

强化学习需要数百万次试错,这在真车上完全不可能:

训练需求 真车 Gazebo仿真
试错次数 几百次就报废 无限次
训练速度 1倍速 可以加速到10-100倍
并行训练 需要多台真车 开多个Gazebo实例
复位成本 手动搬回起点 代码一键复位

实例:训练一个简单的巡线RL模型,真车可能需要3个月+损坏5台车,仿真只需要1周+电费。

1.1.5 提前发现算法缺陷

仿真中可以轻松制造"事故场景":

  • 突然的强光照射(模拟阳光直射摄像头);
  • 赛道上有污渍(模拟线条部分缺失);
  • 传感器故障(模拟某个像素坏点);

这些在真车上很难刻意制造,但在仿真中可以随时开启。提前让你的算法适应这些情况,比赛时就不会翻车。

1.2 环境搭建步骤

走马观碑组Gazebo仿真环境搭建主要包含以下几个步骤:

① 环境准备(ubuntu + ROS2):这个可以参考《ROS2概述和基于RK3588的环境搭建》;

② 小车建模(URDF):有关URFD介绍可以参考《ROS2URDF建模》;

③ 赛道建模(World);

④ 视觉巡线算法开发。

1.2.1 工程目录简介

我们可以先创建工程目录,创建目录car_ws

zhengyang@ubuntu:~$ cd /opt/2k0300/loongson_2k300_lib
zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib$ mkdir -p car_ws/src
zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib$ cd car_ws/src

完整的目录结构大致如下,这个我们后续内容会依次创建:

car_ws/
├── src/
│   ├── car_description/      # 功能包1:机器人URDF模型
│   ├── car_gazebo/           # 功能包2:Gazebo仿真
│   └── car_vision/           # 功能包3:视觉算法

ROS的开发规范中,src/ 下的每个子目录叫功能包(Package),而不是独立项目。它们共同组成一个完整的机器人项目。

功能包 职责 修改频率
car_description 小车的物理模型(尺寸、颜色、传感器位置) 低(硬件确定后很少改)
car_gazebo 仿真环境、赛道、启动脚本 中(换赛道时需要改)
car_vision 图像处理、巡线算法 高(天天调参)
1.2.2 功能包关系

功能包之间的协作关系如下:

启动顺序:
1. car_gazebo 启动仿真世界,生成小车模型
   └── 调用 car_description 中的 car.urdf 描述小车长什么样

2. car_vision 订阅摄像头图像
   └── 处理图像 → 发布速度指令

3. car_gazebo 中的 Gazebo 接收速度指令
   └── 驱动仿真小车运动

二、小车建模

创建car_descriptionPython版本的功能包;

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ ros2 pkg create --build-type ament_python car_description

运行成功后,终端会显示创建的文件和目录信息。此时, car_description 功能包目录结构将如下所示:

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ tree ./car_description/
./car_description/
├── car_description  # 核心Python模块目录,用于存放Python代码
│   └── __init__.py
├── package.xml      # 功能包的描述文件(含依赖信息)
├── resource         # 资源文件夹
│   └── car_description
├── setup.cfg        # setuptools 的配置文件 
├── setup.py         # Python 包的安装脚本
└── test             # 测试文件夹

2.1 子目录

功能包创建好了,但按照规划我们需要在 car_description 中存放小车的URDF模型文件。这些不是.py文件,放在自动生成的 car_description 子目录下并不合适。

我们可以手动创建多个目录来更好地组织文件:

  • urdf: 专门存放 .urdf.xacro 模型文件;
  • launch:保存相关启动文件;
  • rviz:保存rviz的配置文件;
  • meshes:放置URDF中引用的模型渲染文件;
  • config: 存放Gazebo控制器的配置文件。

在终端中执行:

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ cd car_description/
zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description$ mkdir urdf config launch rviz meshes

我们需要修改setup.py文件,添加配置文件:

import os
from glob import glob

    ...

    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*.launch.py'))),
        (os.path.join('share', package_name, 'urdf'), glob(os.path.join('urdf', '*.*'))),
        (os.path.join('share', package_name, 'urdf/sensors'), glob(os.path.join('urdf/sensors', '*.*'))),
        (os.path.join('share', package_name, 'meshes'), glob(os.path.join('meshes', '*.*'))),
        (os.path.join('share', package_name, 'rviz'), glob(os.path.join('rviz', '*.rviz'))),
        (os.path.join('share', package_name, 'config'), glob(os.path.join('config', '*.*'))),
    ],

    ...

2.2 模型文件

接下来就是编写一个完整的 car.xacro 文件,这个模型包含车身、三个轮子、摄像头传感器,并且配置了Gazebo仿真所需的插件;

首先进入 urdf 目录并创建文件:

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description$ cd urdf/
zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description/urdf$ vim car.xacro

内容如下:

点击查看详情
<?xml version="1.0"?>
<robot name="f_car_model" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- ==================== 1. 核心参数定义 (基于实测数据) ==================== -->

  <!-- 车身尺寸 (单位:米) -->
  <!-- 总长23.2cm = 后底盘14cm + 前支架9.2cm -->
  <xacro:property name="main_body_len" value="0.14"/>   <!-- 后部底盘 14cm -->
  <xacro:property name="main_body_width" value="0.16"/> <!-- 后部宽 16cm -->
  <xacro:property name="main_body_height" value="0.064"/> <!-- 车身总高 6.4cm -->

  <xacro:property name="nose_len" value="0.092"/>      <!-- 前部支架 9.2cm -->
  <xacro:property name="nose_width" value="0.072"/>    <!-- 前部宽 7.2cm -->
  <xacro:property name="nose_height" value="0.064"/>   <!-- 与车身同高 -->

  <!-- 轮子参数 (直径6.4cm) -->
  <xacro:property name="wheel_diameter" value="0.064"/>
  <xacro:property name="wheel_radius" value="0.032"/>
  <xacro:property name="wheel_width" value="0.027"/>   <!-- 宽度2.7cm -->
  <xacro:property name="wheel_track" value="0.155"/>   <!-- 轮距15.5cm -->

  <!-- 万向轮参数 -->
  <!-- 万向轮整体参数 -->
  <xacro:property name="caster_total_height" value="0.058"/>  <!-- 总高5.8cm -->
  <xacro:property name="caster_total_width" value="0.028"/>  <!-- 总宽2.8cm -->
  <xacro:property name="caster_small_wheel_radius" value="0.006"/> <!-- 小轮半径1.2cm -->
  <xacro:property name="caster_offset_x" value="0.116"/>  <!-- 万向轮位于前部支架下方 -->
  
  <!-- 万向轮支架偏移(使小轮接触地面) -->
  <xacro:property name="caster_mount_height" value="${caster_total_height - caster_small_wheel_radius*2}"/>

  <!-- 摄像头安装位置 -->
  <xacro:property name="camera_x" value="${main_body_len/2 + nose_len/2}"/> <!-- 车头最前端 -->
  <xacro:property name="camera_y" value="0.0"/>
  <xacro:property name="camera_z" value="0.2"/>        <!-- 立杆 -->
  <xacro:property name="camera_pitch" value="0.2"/>    <!-- 俯视角度约11.5度 -->
  <xacro:property name="camera_roll" value="0.0"/>
  <xacro:property name="camera_yaw" value="0.0"/>

  <!-- 质量参数(根据实际尺寸调整) -->
  <xacro:property name="mass_body" value="0.65"/>
  <xacro:property name="mass_wheel" value="0.08"/>
  <xacro:property name="mass_caster" value="0.03"/>
  <xacro:property name="mass_caster_mount" value="0.02"/>

  <!-- ==================== 2. 材质定义 ==================== -->
  <material name="black">
    <color rgba="0.1 0.1 0.1 1.0"/>
  </material>
  <material name="blue">
    <color rgba="0.0 0.0 0.6 1.0"/>
  </material>
  <material name="white">
    <color rgba="0.9 0.9 0.9 1.0"/>
  </material>
  <material name="silver">
    <color rgba="0.7 0.7 0.7 1.0"/>
  </material>
  <material name="gray">
    <color rgba="0.4 0.4 0.4 1.0"/>
  </material>

  <!-- ==================== 3. 宏定义:轮子 ==================== -->
  <xacro:macro name="wheel" params="prefix parent *origin">
    <link name="${prefix}_wheel">
      <visual>
        <geometry>
          <cylinder radius="${wheel_radius}" length="${wheel_width}"/>
        </geometry>
        <material name="black"/>
        <origin xyz="0 0 0" rpy="1.5707 0 0"/> <!-- 旋转90度让轮子立起来 -->
      </visual>
      <collision>
        <geometry>
          <cylinder radius="${wheel_radius}" length="${wheel_width}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="1.5707 0 0"/>
      </collision>
      <inertial>
        <mass value="${mass_wheel}"/>
        <inertia ixx="0.0005" ixy="0.0" ixz="0.0" iyy="0.0005" iyz="0.0" izz="0.0005"/>
      </inertial>
    </link>

    <joint name="${prefix}_wheel_joint" type="continuous">
      <parent link="${parent}"/>
      <child link="${prefix}_wheel"/>
      <axis xyz="0 1 0"/> <!-- 绕Y轴旋转 -->
      <xacro:insert_block name="origin"/>
    </joint>

    <!-- Gazebo 轮胎摩擦属性 -->
    <gazebo reference="${prefix}_wheel">
      <material>Gazebo/Black</material>
      <mu1 value="1.2"/> <!-- 摩擦系数 -->
      <mu2 value="1.2"/>
      <kp value="10000000.0" />
      <kd value="10.0" />
    </gazebo>
  </xacro:macro>

  <!-- ==================== 4. 车身主体 (Base Link) ==================== -->
  <link name="base_link">
    <!-- 视觉部分:后部主体 -->
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="${main_body_len} ${main_body_width} ${main_body_height}"/>
      </geometry>
      <material name="blue"/>
    </visual>

    <!-- 视觉部分:前部窄支架 -->
    <visual>
      <origin xyz="${main_body_len/2 + nose_len/2} 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="${nose_len} ${nose_width} ${nose_height}"/>
      </geometry>
      <material name="silver"/>
    </visual>

    <!-- 碰撞属性 (简化为两个盒子,提高仿真稳定性) -->
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="${main_body_len} ${main_body_width} ${main_body_height}"/>
      </geometry>
    </collision>
    <collision>
      <origin xyz="${main_body_len/2 + nose_len/2} 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="${nose_len} ${nose_width} ${nose_height}"/>
      </geometry>
    </collision>

    <!-- 惯性参数 (重心略微后移,模拟电机重量) -->
    <inertial>
      <origin xyz="-0.02 0 0" rpy="0 0 0"/>
      <mass value="${mass_body}"/>
      <inertia ixx="0.0035" ixy="0.0" ixz="0.0" iyy="0.0055" iyz="0.0" izz="0.007"/>
    </inertial>
  </link>

  <!-- ==================== 5. 轮子实例化 ==================== -->
  <!-- 左后轮 -->
  <xacro:wheel prefix="left" parent="base_link">
    <origin xyz="${-main_body_len/2 + 0.01} ${wheel_track/2} ${-wheel_radius}" rpy="0 0 0"/>
  </xacro:wheel>

  <!-- 右后轮 -->
  <xacro:wheel prefix="right" parent="base_link">
    <origin xyz="${-main_body_len/2 + 0.01} ${-wheel_track/2} ${-wheel_radius}" rpy="0 0 0"/>
  </xacro:wheel>

  <!-- ==================== 6. 万向轮(完整结构) ==================== -->
  
  <!-- 万向轮支架 -->
  <link name="caster_mount">
    <visual>
      <geometry>
        <box size="0.04 0.028 0.058"/>
      </geometry>
      <material name="gray"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
    </visual>
    <collision>
      <geometry>
        <box size="0.04 0.028 0.058"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="${mass_caster_mount}"/>
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
    </inertial>
  </link>

  <joint name="caster_mount_joint" type="fixed">
    <parent link="base_link"/>
    <child link="caster_mount"/>
    <origin xyz="${caster_offset_x} 0 ${-main_body_height/2}" rpy="0 0 0"/>
  </joint>

  <!-- 万向轮小轮 -->
  <link name="caster_small_wheel">
    <visual>
      <geometry>
        <cylinder radius="${caster_small_wheel_radius}" length="0.02"/>
      </geometry>
      <material name="black"/>
      <origin xyz="0 0 0" rpy="1.5707 0 0"/>
    </visual>
    <collision>
      <geometry>
        <cylinder radius="${caster_small_wheel_radius}" length="0.02"/>
      </geometry>
      <origin xyz="0 0 0" rpy="1.5707 0 0"/>
    </collision>
    <inertial>
      <mass value="${mass_caster}"/>
      <inertia ixx="0.00005" ixy="0.0" ixz="0.0" iyy="0.00005" iyz="0.0" izz="0.00005"/>
    </inertial>
  </link>

  <joint name="caster_small_wheel_joint" type="continuous">
    <parent link="caster_mount"/>
    <child link="caster_small_wheel"/>
    <axis xyz="1 0 0"/>  <!-- 绕X轴旋转,模拟万向轮小轮滚动 -->
    <origin xyz="0 0 ${-caster_total_height/2 + caster_small_wheel_radius}" rpy="0 0 0"/>
  </joint>

  <!-- Gazebo 万向轮属性 -->
  <gazebo reference="caster_mount">
    <material>Gazebo/Gray</material>
    <mu1 value="0.3"/>
    <mu2 value="0.3"/>
  </gazebo>

  <gazebo reference="caster_small_wheel">
    <material>Gazebo/Black</material>
    <mu1 value="0.8"/>
    <mu2 value="0.8"/>
  </gazebo>

  <!-- ==================== 7. 摄像头链接 ==================== -->
  <link name="camera_link">
    <visual>
      <geometry>
        <box size="0.04 0.04 0.04"/>
      </geometry>
      <material name="black"/>
    </visual>
  </link>

  <joint name="camera_joint" type="fixed">
    <parent link="base_link"/>
    <child link="camera_link"/>
    <!-- 摄像头安装在车头立杆顶端 -->
    <origin xyz="${camera_x} ${camera_y} ${camera_z}" rpy="${camera_roll} ${camera_pitch} ${camera_yaw}"/>
  </joint>

  <!-- ==================== 8. Gazebo 插件 ==================== -->
  <gazebo>
    <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
      <rosDebugLevel>Debug</rosDebugLevel>
      <publishWheelTF>false</publishWheelTF>
      <robotNamespace>/</robotNamespace>
      <publishTf>1</publishTf>
      <publishWheelJointState>true</publishWheelJointState>
      <alwaysOn>true</alwaysOn>
      <updateRate>50.0</updateRate>
      <leftJoint>left_wheel_joint</leftJoint>
      <rightJoint>right_wheel_joint</rightJoint>
      <wheelSeparation>${wheel_track}</wheelSeparation>
      <wheelDiameter>${wheel_diameter}</wheelDiameter>
      <broadcastTF>1</broadcastTF>
      <wheelTorque>5.0</wheelTorque>
      <wheelAcceleration>1.5</wheelAcceleration>
      <commandTopic>cmd_vel</commandTopic>
      <odometryFrame>odom</odometryFrame>
      <odometryTopic>odom</odometryTopic>
      <robotBaseFrame>base_link</robotBaseFrame>
    </plugin>
  </gazebo>

  <!-- 摄像头插件(160x128 @ 60fps,广角120度) -->
  <gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
      <update_rate>60.0</update_rate>
      <camera name="head">
        <horizontal_fov>2.09</horizontal_fov> <!-- 约120度广角 -->
        <td>
          <width>160</width>
          <height>128</height>
          <format>R8G8B8</format>
        </td>
        <clip>
          <near>0.02</near>
          <far>10.0</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>camera</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>camera_link</frameName>
        <hackBaseline>0.07</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
  </gazebo>

</robot>

这里我们通过通过 nosemain_body 的组合来模拟车模前窄后宽的形状,这更符合F车模的真实外观;

  • 长:23.2cm、宽18cm、高6.4cm
  • 车轮:直径6.4cm、宽度2.7cm、轮距15.5cm
  • 万向轮:直径5.8cm、宽度2.8cm、小轮直径1.2cm
2.2.1 车身几何结构

使用了两个 <box> 来拼接车身;

  • 后部 (main_body):尺寸0.14m x 0.16m,这是电机和后轮所在的位置,比较宽;
  • 前部 (nose):尺寸0.092m x 0.072m,这是向前延伸的部分,模拟真实的窄支架;

总长:0.14 + 0.092 = 0.232m

当然如果熟悉SolidWorksFusion 360可以按照图片画一个精确的3D模型,将其导出为 .stl.dae 文件。在URDF中,把 <box> 标签换成:

<mesh filename="package://your_package/meshes/f_car_body.stl"/>

这样在rvizGazebo中看到的就完全是一模一样的车了。

2.2.2 轮距与轮子

轮距wheel_track 设为0.155m。轮子坐标通过 ${-main_body_len/2 + 0.01} 计算,确保轮子安装在后底盘的边缘,而不是车身中心。

2.2.3 万向轮位置

万向轮安装在 caster_offset_x处,这大约在前部支架的中间位置,既保证了支撑稳定性,又不会因为太靠前而在转弯时产生过大的阻力矩。

2.2.4 摄像头高度

为了适应“走马观碑”组别,我将摄像头高度设定为离地约20cm (camera_z),并增加了一个俯仰角 camera_pitch,这更符合实际比赛中俯视赛道的情况。

2.2.5 Gazebo仿真支持

我们在模型最后添加了Gazebo插件;

  • 差速驱动插件:可以让小车动起来,对应真车:电机驱动器 + 编码器;
  • 摄像头插件:可以让车看见,对应真车:USB摄像头;
  • 轮胎摩擦属性:物理属性标签,让车像真车一样运动。

Gazebo仿真支持 = 给虚拟小车装上“电机、摄像头、物理轮胎”,让它能在虚拟世界里被控制、感知环境,像真车一样跑起来。

2.2.5.1 差速驱动插件

libgazebo_ros_diff_drive.soROSGazebo通信的桥梁,它的作用是:接收ROS的速度指令,转化为车轮的物理转动;同时将车轮的转动转化为里程计数据发回给ROS。即订阅 /cmd_vel 指令,计算左右轮速度,驱动小车运动;同时发布里程计 /odom

  <gazebo>
    <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
      <rosDebugLevel>Debug</rosDebugLevel>
      <publishWheelTF>false</publishWheelTF>
      <robotNamespace>/</robotNamespace>
      <publishTf>1</publishTf>
      <publishWheelJointState>true</publishWheelJointState>
      <alwaysOn>true</alwaysOn>
      <updateRate>50.0</updateRate>
      <leftJoint>left_wheel_joint</leftJoint>
      <rightJoint>right_wheel_joint</rightJoint>
      <wheelSeparation>${wheel_track}</wheelSeparation>
      <wheelDiameter>${wheel_diameter}</wheelDiameter>
      <broadcastTF>1</broadcastTF>
      <wheelTorque>5</wheelTorque>
      <wheelAcceleration>1.5</wheelAcceleration>
      <commandTopic>cmd_vel</commandTopic>
      <odometryFrame>odom</odometryFrame>
      <odometryTopic>odom</odometryTopic>
      <robotBaseFrame>base_link</robotBaseFrame>
    </plugin>
  </gazebo>

其中:

  • name: 插件在Gazebo内部的名称,随便起,只要不重复就行;

  • filename:核心文件。这是ROS官方提供的差速驱动库。

  • rosDebugLevel: 调试等级。设为 Debug 会在终端打印大量信息(比如“我收到速度指令了”、“我发布里程计了”)。调试时很有用,正式运行可以改为 InfoWarn

  • robotNamespace: 命名空间。设为 / 表示使用全局命名空间。如果你有多台小车(比如小车A、小车B),这里可以设为 /robot_A,这样指令就不会串台;

  • leftJoint / rightJoint: 这里必须填在URDF中定义的关节名称;

  • wheelSeparation: 左右轮之间的距离(即轮距),插件利用这个数据计算角速度:差速越大,转得越快;

  • wheelDiameter:轮子直径,插件利用这个数据计算线速度:轮子转一圈走多远;

  • wheelTorque: 最大输出扭矩(单位Nm),决定了车有多“大力”;

  • wheelAcceleration: 角加速度决定了车速变化的快慢。设为1.5表示速度增加比较平滑,不会瞬间从0变到100

  • commandTopic: 输入话题。插件会订阅这个话题(通常是 geometry_msgs/Twist 类型)。给这个topic发速度指令,车就会动;

  • odometryTopic: 输出话题。插件会把里程计数据发布到这个topic(通常是 nav_msgs/Odometry 类型);

  • odometryFrame: 里程计的父坐标系,通常叫 odom

  • robotBaseFrame: 机器人的基坐标系,通常叫base_link,插件会自动发布 odom -> base_linkTF变换;

  • alwaysOn: 只要仿真开始,插件就一直运行;

  • updateRate: 控制频率(Hz)。100Hz表示每秒计算100次物理响应,足够流畅;

  • publishTf: 是否发布TF变换树(必须设为1,否则导航包无法定位);

  • publishWheelTF: 是否发布轮子相对于车身的TF。一般不需要,设为 false 节省资源;

  • publishWheelJointState: 是否发布轮子的关节状态(位置、速度)。设为 true 后,可以在ROS里看到 /joint_states 话题,看到轮子转得多快。

2.2.5.2 摄像头插件

接着是是给小车装上了“眼睛”。定义了一个针孔相机模型,并配置了ROS驱动,让Gazebo能把渲染出的图像发布成ROS话题(实时渲染图像并发布到ROS话题 /camera/image_raw)。

  <gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
      <update_rate>60.0</update_rate>
      <camera name="head">
        <horizontal_fov>2.09</horizontal_fov> <!-- 约120度 -->
        <image>
          <width>160</width>
          <height>128</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
      </camera>
      <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>camera</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>camera_link</frameName>
        <hackBaseline>0.07</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
  </gazebo>

传感器基础配置:

  • type="camera": 指定这是一个普通的光学摄像头(区别于深度相机 depth 或 激光雷达 ray);
  • name="camera1": 传感器在Gazebo内部的名称,方便在Gazebo界面里调试;
  • update_rate: 刷新率 (Hz),设为60.0表示每秒生成60帧图像;

相机光学参数:

  • horizontal_fov: 水平视场角(单位:弧度),智能车竞赛通常使用广角镜头(如120度甚至更大)。如果觉得视野太窄,车还没看到弯道就已经撞墙了,可以把这个值改大,例如2.09 (120度);
  • width/height: 图像分辨率;
  • format:像素格式;
  • near: 最近裁剪距离(米),小于0.02米(2厘米)的物体不会被渲染。如果摄像头装得太低,地面可能会直接变黑或消失;
  • far: 最远裁剪距离(米),超过300米 的物体看不见。对于室内赛道,这个值无所谓;如果是室外大场景,要调大。

ROS插件配置:

  • filename:加载ROS的摄像头驱动库;
  • alwaysOn: 仿真一开始就启动摄像头;
  • updateRate: 注意!这里设为 0.0 的意思是“跟随 <sensor> 标签里的 update_rate”。如果这里设为非零值,它会覆盖上面的60Hz。建议保持0.0
  • cameraName: 话题的前缀;
  • imageTopicName: 图像话题名,最终发布的Topic/camera/image_raw
  • cameraInfoTopicName: 相机内参话题名最终发布的Topic/camera/camera_info。里面包含焦距、光心等标定参数;
  • frameNameTF坐标系名称;
    • 发布的图像消息里会包含 header.frame_id = "camera_link"
    • 必须和URDF中摄像头的 <link name="..."> 名字一致,否则TF变换会报错;
  • hackBaseline: 基线距离,这通常用于双目相机(两个镜头之间的距离)。单目相机设为0即可,这里保留默认值不影响单目使用;
  • 畸变参数:这里全是 0.0,意味着图像是完美的,没有畸变;
    • 现实对比:真实的广角摄像头会有“桶形畸变”(直线变弯);
    • 仿真优势:在仿真里关闭畸变是好事!这样图像处理算法(比如霍夫变换找直线)会更容易写,不用先做去畸变处理。
2.2.5.3 轮胎摩擦属性

定义前万向轮在Gazebo仿真环境中的物理属性和外观;

  <gazebo reference="caster_wheel">
    <material>Gazebo/White</material>
    <mu1 value="0.1"/> <!-- 万向轮摩擦力较小 -->
    <mu2 value="0.1"/>
  </gazebo>

其中:

  • mu1 (纵向摩擦系数):代表轮子滚动方向的摩擦力,这里设为 0.1(非常小);
    • 为什么这么小?真实的万向轮(或球头)设计初衷就是为了减小阻力。如果这个值太大(比如设为 1.0,像橡胶轮胎一样),万向轮就会像刹车片一样死死“咬”住地面,导致小车根本推不动,或者在转弯时发生剧烈抖动、卡死;
  • mu2 (横向摩擦系数):代表轮子侧滑方向的摩擦力,这里也设为 0.1
    • 作用:允许万向轮在转弯时能够顺滑地侧向滑动。

2.3 launch文件

launch文件夹下创建display.launch.py文件;

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch_ros.parameter_descriptions import ParameterValue
from launch_ros.actions import Node
from launch.substitutions import Command, LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
import os

def generate_launch_description():
    # xacro 文件路径(注意扩展名是 .xacro)
    xacro_path = os.path.join(
        get_package_share_directory('car_description'),
        'urdf',
        'car.xacro'  # 关键:改为 .xacro
    )
    
    # 声明 model 参数
    model_arg = DeclareLaunchArgument(
        name='model',
        default_value=xacro_path,
        description='Absolute path to robot xacro file'
    )
    
    # 使用 xacro 命令解析 URDF
    robot_description = ParameterValue(
        Command(['xacro ', LaunchConfiguration('model')]),
        value_type=str
    )
    
    return LaunchDescription([
        model_arg,  # 必须包含这个声明
        
        # 机器人状态发布器
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            output='screen',
            parameters=[{'robot_description': robot_description}]
        ),
        
        # 关节状态发布器 GUI(可手动拖动关节)
        Node(
            package='joint_state_publisher_gui',
            executable='joint_state_publisher_gui',
            name='joint_state_publisher_gui'
        ),
        
        # RViz2 可视化
        Node(
            package='rviz2',
            executable='rviz2',
            name='rviz2',
            arguments=['-d', os.path.join(get_package_share_directory('car_description'), 'rviz', 'car_display.rviz')],
	    	output='screen'
        )
    ])

这个Launch文件主要做三件事:

  • 加载机器人URDF模型(支持xacro格式);
  • 发布机器人的状态变换(TF);
  • rviz2中可视化机器人。
2.3.1 节点

脚本运行会创建以下几个节点:

  • joint_state_publisher_gui:发布每个joint(除fixed类型)的状态,可以通过UI界面对joint进行控制;
  • robot_state_publisher:将机器人各个linksjoints之间的关系,通过TF的形式,整理成三维姿态信息发布。
  • rviz2:在rviz2中可视化机器人;

joint_state_publisher这是一个官方ROS2包,主要功能:

  • 输入:
    • 读取URDF中的关节定义;
    • 接收用户或程序指定的关节角度;
  • 输出:
    • 发布 /joint_states 话题,消息类型为 sensor_msgs/msg/JointState
    • 包含所有关节的名称、位置、速度、力等信息。
2.3.2 数据流与节点关系

数据流与节点关系:

用户通过滑动条/GUI或程序 → joint_state_publisher_gui
                                     ↓ 发布/joint_states话题
                        robot_state_publisher
                                     ↓ 计算并发布TF变换
                              rviz2 和其他节点
                                     ↓ 接收TF并可视化

2.4 car_display.rviz

创建rviz配置文件,避免手动设置rviz,在rviz目录下新建car_display.rviz文件;

Panels:
  - Class: rviz_common/Displays
    Name: Displays
  - Class: rviz_common/Views
    Name: Views
Visualization Manager:
  Class: ""
  Displays:
    - Class: rviz_default_plugins/Grid
      Name: Grid
      Value: true
    - Alpha: 0.8
      Class: rviz_default_plugins/RobotModel
      Description Source: Topic
      Description Topic:
        Value: /robot_description
      Enabled: true
      Name: RobotModel
      Value: true
    - Class: rviz_default_plugins/TF
      Name: TF
      Value: true
  Global Options:
    Fixed Frame: base_link
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz_default_plugins/MoveCamera
  Value: true
  Views:
    Current:
      Class: rviz_default_plugins/Orbit
      Distance: 1.7
      Name: Current View
      Pitch: 0.33
      Value: Orbit (rviz)
      Yaw: 5.5
Window Geometry:
  Height: 800
  Width: 1200

2.5 编译运行

2.4.1 编译

car_ws 目录下编译并检查:

zhengyang@ubuntu:~$ cd /opt/2k0300/loongson_2k300_lib/car_ws

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws$ colcon build --paths src/car_description
.....
Finished <<< car_description [0.92s]

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws$ source install/setup.sh
2.4.2 运行

启动终端,运行如下命令;

zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws$ ros2 launch car_description display.launch.py

可以看到rviz窗口打开,并且显示了小车模型;

取消左侧的TF勾选,可以更加清晰的看到小车模型;

三、赛道建模

四、视觉巡线算法

posted @ 2026-04-05 17:58  大奥特曼打小怪兽  阅读(42)  评论(0)    收藏  举报
如果有任何技术小问题,欢迎大家交流沟通,共同进步