一文带你完成20届智能车备赛

一文带你完成20届智能车备赛

后续内容更新中,预计7.4完成全部内容更新。

前言

20届智能车备赛已经进入紧张阶段。作为19届的参赛选手,本文将分享我的经验和建议,帮助大家更好地完成比赛。内容涵盖比赛规则、车模要求、任务拆解、算法实现等方面。

如果你是第一次接触智能车,建议先阅读官方的 第二十届全国大学生智能车竞赛-地瓜机器人智慧医疗挑战赛规则,了解比赛的基本流程和要求。


比赛规则

详细规则请参考:
第二十届全国大学生智能车竞赛-地瓜机器人智慧医疗挑战赛规则

资料获取可参考:
第二十届全国大学生智能汽车竞赛地瓜机器人创意组智慧医疗挑战赛

个人规则理解:待补充……


车模要求与硬件平台

车模仅可选择官方提供的两种型号。

注意:请勿擅自更换核心部件(如拆壳、换电机等),否则将被取消资格。允许加装风扇散热或更换更好的 WiFi 模块。

设备名称 主控制器 核心算力 (BPU) 内存 关键传感器 个人评价
OriginCar 地瓜机器人 RDK X3 5 TOPS 4GB LPDDR4 单目摄像头 (1080P) 基础款,能完成所有任务,但对算法优化要求高。
OriginCar Pro 地瓜机器人 RDK X5 10 TOPS 8GB LPDDR4 单目摄像头 (1080P) + 深度相机 强烈推荐!算力翻倍,AI模型运行更流畅,CPU和内存全面升级。

ROS包迁移

如首次接触 ROS2,建议先阅读 ROS2入门教程

RDK X3

  1. 按 RDK 手册烧录最新 RDK X3 镜像到 SD 卡,插入 OriginCar,上电后红灯常亮、绿灯闪烁为正常状态。

tips:建议烧录 server 端镜像以节省计算资源。

  1. 配置网络,确保 OriginCar 可联网,PC 端可通过 SSH 连接。

    • 有线连接时,确保 IP 同网段。默认静态 IP:192.168.127.10
  2. SSH 连接后,查看镜像信息:

    rdk_os info
    
  3. 更新 miniboot 及系统:

    sudo rdk-miniboot-update
    sudo apt update && sudo apt full-upgrade
    

    注意:截至 2025.7.1,RDK X3 最新镜像为 v3.0.0,若遇 GPG key 错误,可用以下命令修复:

    sudo apt install gpg
    cp /usr/share/keyrings/ros-archive-keyring.gpg /usr/share/keyrings/ros-archive-keyring.gpg.b && rm /usr/share/keyrings/ros-archive-keyring.gpg
    sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key | sudo gpg --dearmor -o /usr/share/keyrings/ros-archive-keyring.gpg 
    echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://mirrors4.tuna.tsinghua.edu.cn/ros2/ubuntu $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
    sudo apt update
    
  4. 迁移官方 origincar 功能包:

    mkdir -p ~/ros2_ws/src
    cd ~/ros2_ws/src
    

    上传官方 origincar 功能包,目录结构如下:

    └── src
       └── origincar
           ├── 3rdparty
           ├── origincar_base
           ├── origincar_bringup
           ├── origincar_description
           └── origincar_msg
    
  5. 安装 colcon build 工具及依赖包:

    pip3 install colcon-common-extensions
    sudo apt install ros-humble-navigation2 ros-humble-nav2-bringup ros-humble-robot-localization ros-humble-teleop-twist-keyboard python3-ament-package ros-humble-ament-cmake
    
  6. 编译 ROS2 功能包:

    cd ~/ros2_ws
    colcon build --symlink-install
    
  7. 启动底盘及键盘控制节点验证:

    source ~/ros2_ws/install/setup.bash
    ros2 launch origincar_bringup origincar_base.launch.py
    

    新开终端:

    source /opt/tros/humble/setup.bash
    ros2 run teleop_twist_keyboard teleop_twist_keyboard
    

RDK X5

  1. 按 RDK 手册烧录最新 RDK X5 镜像到 SD 卡,插入 OriginCar Pro,上电后绿灯常亮、红灯闪烁为正常状态。

  2. 配置网络,确保 OriginCar 可联网,PC 端可通过 SSH 连接,也可以使用 RDK Studio 闪连功能。

    • 有线连接时,确保 IP 同网段。默认静态 IP:192.168.127.10
  3. SSH 连接后,查看镜像信息:

    rdk_os info
    
  4. 更新 miniboot 及系统:

    sudo rdk-miniboot-update
    sudo apt update && sudo apt full-upgrade
    
  5. 迁移官方 origincar 功能包:

    mkdir -p ~/ros2_ws/src
    cd ~/ros2_ws/src
    

    上传官方 origincar 功能包,目录结构如下:

    └── src
       └── origincar
           ├── 3rdparty
           ├── origincar_base
           ├── origincar_bringup
           ├── origincar_description
           └── origincar_msg
    
  6. 安装 colcon build 工具及依赖包:

    pip3 install colcon-common-extensions
    sudo apt install ros-humble-navigation2 ros-humble-nav2-bringup ros-humble-robot-localization ros-humble-teleop-twist-keyboard python3-ament-package
    
  7. 编译 ROS2 功能包:

    cd ~/ros2_ws
    colcon build --symlink-install
    
  8. 启动底盘及键盘控制节点验证:

    source ~/ros2_ws/install/setup.bash
    ros2 launch origincar_bringup origincar_base.launch.py
    

    新开终端:

    source /opt/tros/humble/setup.bash
    ros2 run teleop_twist_keyboard teleop_twist_keyboard
    

任务一

任务一可拆解为:巡线 + 避障 + 扫码

1. 巡线

推荐使用 Nodehub 中诺哥的三个功能包,稍作修改即可高效完成任务。
本人 19 届备赛也采用此方案,效果良好:

功能包地址:

我们可以在我们的 ROS2 工作空间中创建一个新的包,将上述功能包下载到本地。

mkdir -p ~/ros2_ws/src/racing_car
cd ~/ros2_ws/src/racing_car

接下来下载对应赛道检测的源码(需要大家根据自己的小车型号进行选择):

# RDK X5
git clone https://github.com/wunuo1/racing_track_detection_resnet.git -b feature-x5
# RDK X3
git clone https://github.com/wunuo1/racing_track_detection_resnet.git -b feature-x3

tips: 若是无法使用 git,可以选择从网页下载 zip 后上传,注意分支。

接下来直接 colcon build 编译即可,记得在编译之前先 source /opt/tros/humble/setup.bash,确保环境变量正确。
若是不想每次都 source,可以在 ~/.bashrc 中添加以下内容:

# 在~/.bashrc中添加以下内容
source /opt/tros/humble/setup.bash
source ~/ros2_ws/install/setup.bash

接下来进行编译:

cd ~/ros2_ws
colcon build --symlink-install

应该可以正常编译通过。有报错应该也只是一些依赖包未安装,可以根据报错提示安装对应的包。
至于大片的 warning 信息,通常是因为缺少一些依赖包或是编译器的警告信息,这些通常不会影响功能实现,有兴趣的同学可以自行查找解决。

接下来可以验证效果,观察功能包中的 launch.py 文件可以发现,主要是起了三个节点,我们这里只留下启动赛道检测的节点,其他的节点可以在启动摄像头时启动,修改后的 launch.py 文件如下:

def generate_launch_description():

   racing_track_detection_resnet18_node = Node(
      package='racing_track_detection_resnet',
      executable='racing_track_detection_resnet',
      output='screen',
      parameters=[
        {"sub_img_topic": "/hbmem_img"},
        {"model_path": "config/race_track_detection.bin"}
      ],
      arguments=['--ros-args', '--log-level', 'warn']
   )

   return LaunchDescription([
      racing_track_detection_resnet18_node
   ])

可以发现,赛道检测节点需要订阅 /hbmem_img 话题,这个话题是摄像头发布后 → nv12 的图像话题。

可以在 origincar_bringup 包自己创建摄像头的 launch 文件,我习惯命名为 camera.launch.py,我们可以在这个文件有关摄像头启动的节点,camera.launch.py 文件内容如下:

import os
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import IncludeLaunchDescription
from ament_index_python import get_package_share_directory

def generate_launch_description():
  nv12_codec_node = IncludeLaunchDescription(
   PythonLaunchDescriptionSource(
    os.path.join(
      get_package_share_directory('hobot_codec'),
      'launch/hobot_codec_decode.launch.py'
    )
   ),
   launch_arguments={
    'codec_in_mode': 'ros',
    'codec_out_mode': 'shared_mem',
    'codec_sub_topic': '/image',
    'codec_pub_topic': '/hbmem_img'
   }.items()
  )

  web_node = IncludeLaunchDescription(
   PythonLaunchDescriptionSource(
    os.path.join(
      get_package_share_directory('websocket'),
      'launch/websocket.launch.py'
    )
   ),
   launch_arguments={
    'websocket_image_topic': '/image',
    'websocket_smart_topic': '/racing_track_center_detection'
   }.items()
  )

  usb_cam_node = Node(
   package='hobot_usb_cam',
   executable='hobot_usb_cam',
   name='hobot_usb_cam',
   parameters=[
    {"camera_calibration_file_path": "/opt/tros/lib/hobot_usb_cam/config/usb_camera_calibration.yaml"},
    {"frame_id": "default_usb_cam"},
    {"framerate": 30},
    {"image_width": 640},
    {"image_height": 480},
    {"io_method": "mmap"},
    {"pixel_format": "mjpeg"},
    {"video_device": "/dev/video8"},
    {"zero_copy": False}
   ],
   arguments=['--ros-args', '--log-level', 'error']
  )

  return LaunchDescription([
   usb_cam_node,
   nv12_codec_node,
   web_node,
  ])

我们使用 hobot_usb_cam 包来启动摄像头,注意这里的 video_device 需要根据实际情况修改,通常是 /dev/video8web_node 是 websocket 的节点,用于将摄像头图像发布到 web 端,nv12_codec_node 是将摄像头图像转换为共享内存格式的节点。
注意:racing_track_detection_resnet 需要订阅 nv12 类型的图像话题,web_node 需要订阅 mjpeg 类型的图像话题和 racing_track_detection_resnet 发布的中心点话题。

不同节点间的订阅关系如下:

hobot_usb_cam -> nv12_codec_node -> racing_track_detection_resnet

hobot_usb_cam -> web_node <- racing_track_detection_resnet

现在我们可以启动摄像头和赛道检测节点了,使用以下命令:

# 进入config目录
cd ~/ros2_ws/src/racing_car/racing_track_detection_resnet/config
ros2 launch racing_track_detection_resnet racing_track_detection_resnet.launch.py

另启动摄像头节点:

ros2 launch origincar_bringup camera.launch.py

由于缺乏维护,可能存在小问题,可以参考以下修改:

这里首先推荐大家使用 vscode 进行代码开发,vscode 支持不同的插件可以帮助你快速的阅读,调整和编写你的代码。具体的有机会再展开。
这里我们主要使用 Remote-ssh 插件进行远程开发。

根据报错:

[racing_track_detection_resnet-1] [WARN] [1751361111.644720579] [GetLineCoordinate]: New publisher discovered on topic '/hbmem_img', offering incompatible QoS. No messages will be sent to it. Last incompatible policy: RELIABILITY_QOS_POLICY

可以发现 /hbmem_img 话题的 QoS 策略不兼容,可以在 racing_track_detection_resnet 节点中添加 QoS 策略,修改 /hbmem_img 订阅的 QoS 策略为 BestEffort,代码如下:

  rclcpp::QoS img_qos(10);
  img_qos.reliability(rclcpp::ReliabilityPolicy::BestEffort);  // 匹配发布者的BEST_EFFORT

  subscriber_hbmem_ =
   this->create_subscription<hbm_img_msgs::msg::HbmMsg1080P>(
    sub_img_topic_,
    img_qos,
    std::bind(&TrackDetectionNode::subscription_callback,
    this,
    std::placeholders::_1)); 

然后重新编译即可,再次启动摄像头和赛道检测节点,应该可以正常工作,大家可以在 web 端查看摄像头图像和赛道检测结果,网址为:ip:8000

大家可以看到给出的模型其实效果一般,这时候就需要大家自己采集数据集训练模型了,具体的模型训练和数据集采集可以参考以下链接:

好的现在我们应该以及得到了基于我们自己的数据集训练的模型,并且以及将他转化成了 bin 文件。
接下来我们需要将模型放到 config 目录下,并且修改 racing_track_detection_resnet.launch.py 文件中的 model_path 参数为我们自己的模型路径。

racing_track_detection_resnet18_node = Node(
   package='racing_track_detection_resnet',
   executable='racing_track_detection_resnet',
   output='screen',
   parameters=[
      {"sub_img_topic": "/hbmem_img"},
      {"model_path": "config/your_model.bin"}  # 替换为你的模型路径
   ],
   arguments=['--ros-args', '--log-level', 'warn']
)

现在我们可以启动赛道检测节点,应该可以看到模型在 web 端的效果。

接下来需要进行巡线控制,我们依旧可以使用 Nodehub 中诺哥的巡线控制功能包,或者自己编写一个简单的巡线控制节点。

cd ~/ros2_ws/src/racing_car
git clone https://github.com/nodehubs/racing_control.git

tips: 若是无法使用 git,可以选择从网页下载 zip 后上传。

接下来编译即可:

cd ~/ros2_ws
colcon build --package-select racing_control --symlink-install

可以修改 racing_control 包中的 launch.py 文件的对应参数实现控制:
巡线用到的参数为:

  • follow_linear_speed
  • follow_angular_ratio

现在我们可以启动巡线控制了,我们需要启动 4 个节点:

  1. origincar_base - 小车底盘节点
  2. camera - 摄像头节点
  3. racing_track_detection_resnet - 赛道检测节点
  4. racing_control - 巡线控制节点
ros2 launch origincar_base origincar_bringup.launch.py
ros2 launch origincar_bringup camera.launch.py
ros2 launch racing_track_detection_resnet racing_track_detection_resnet.launch.py
ros2 launch racing_control racing_control.launch.py

现在我们可以在 web 端查看摄像头图像和赛道检测结果,并且小车应该可以自动巡线了。
实际在比赛中,我们不需要在 web 端查看摄像头图像和赛道检测结果,我们可以新建一个 launch 文件,不包含 webnode

import os
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import IncludeLaunchDescription
from ament_index_python import get_package_share_directory

def generate_launch_description():
  nv12_codec_node = IncludeLaunchDescription(
   PythonLaunchDescriptionSource(
    os.path.join(
      get_package_share_directory('hobot_codec'),
      'launch/hobot_codec_decode.launch.py'
    )
   ),
   launch_arguments={
    'codec_in_mode': 'ros',
    'codec_out_mode': 'shared_mem',
    'codec_sub_topic': '/image',
    'codec_pub_topic': '/hbmem_img'
   }.items()
  )

  usb_cam_node = Node(
   package='hobot_usb_cam',
   executable='hobot_usb_cam',
   name='hobot_usb_cam',
   parameters=[
    {"camera_calibration_file_path": "/opt/tros/lib/hobot_usb_cam/config/usb_camera_calibration.yaml"},
    {"frame_id": "default_usb_cam"},
    {"framerate": 30},
    {"image_width": 640},
    {"image_height": 480},
    {"io_method": "mmap"},
    {"pixel_format": "mjpeg"},
    {"video_device": "/dev/video8"},
    {"zero_copy": False}
   ],
   arguments=['--ros-args', '--log-level', 'error']
  )

  return LaunchDescription([
   usb_cam_node,
   nv12_codec_node,
  ])

仅供参考,这一定不是你最终版本的 launch 文件。

接下来我将介绍如何进行避障和扫码。

2. 避障

3. 扫码

任务二

任务二可以简单理解为小车遥控 + 大模型图生文

2 个赞