Skip to content

【In Develop】Shenzhen MSU-BIT University PolarBear Team's Sentry Navigation Sim/Real Package for RoboMaster2025. QQ group: 932119307

License

Notifications You must be signed in to change notification settings

SMBU-PolarBear-Robotics-Team/pb2025_sentry_nav

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

42 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

pb2025_sentry_nav

License Build and Test pre-commit

深圳北理莫斯科大学 北极熊战队 2025 赛季哨兵导航仿真/实车包

PolarBear Logo

Bilibili: 谁说在家不能调车!?更适合新手宝宝的 RM 导航仿真

NAV2 动态避障
rmuc_lidar_on_chassis_nav rmuc_lidar_on_chassis_nav

1. 项目介绍

本项目基于 NAV2 导航框架 并参考学习了 autonomous_exploration_development_environment 的设计。

  • 关于坐标变换:

    本项目大幅优化了坐标变换逻辑,考虑雷达原点 lidar_odom 与 底盘原点 odom 之间的隐式变换。

    mid360 倾斜侧放在底盘上,使用 point_lio 里程计,small_gicp 重定位,loam_interface 会将 point_lio 输出的 /cloud_registeredlidar_odom 系转换到 odom 系,sensor_scan_generationodom 系的点云转换到 front_mid360 系,并发布变换 odom -> chassis

    frames_2025_1_7

  • 关于路径规划:

    使用 NAV2 默认的 Global Planner 作为全局路径规划器,pb_omni_pid_pursuit_controller 作为路径跟踪器。

  • namespace:

    为了后续拓展多机器人,本项目引入 namespace 的设计,与 ROS 相关的 node, topic, action 等都加入了 namespace 前缀。如需查看 tf tree,请使用命令 ros2 run rqt_tf_tree rqt_tf_tree --ros-args -r /tf:=tf -r /tf_static:=tf_static -r __ns:=/red_standard_robot1

  • LiDAR:

    Livox mid360 倾斜侧放在底盘上。

    注:仿真环境中,实际上 point pattern 为 velodyne 样式的机械式扫描。此外,由于仿真器中输出的 PointCloud 缺少部分 field,导致 point_lio 无法正常估计状态,故仿真器输出的点云经过 ign_sim_pointcloud_tool 处理添加 time field。

  • 文件结构

    .
    ├── fake_vel_transform                  # 虚拟速度参考坐标系,以应对云台扫描模式自旋,详见子仓库 README
    ├── ign_sim_pointcloud_tool             # 仿真器点云处理工具
    ├── livox_ros_driver2                   # Livox 驱动
    ├── loam_interface                      # point_lio 等里程计算法接口
    ├── pb_teleop_twist_joy                 # 手柄控制
    ├── pb2025_nav_bringup                  # 启动文件
    ├── pb2025_sentry_nav                   # 本仓库功能包描述文件
    ├── pb_omni_pid_pursuit_controller      # 路径跟踪控制器
    ├── point_lio                           # 里程计
    ├── sensor_scan_generation              # 点云相关坐标变换
    ├── small_gicp_relocalization           # 重定位
    └── terrain_analysis                    # 分割出非地面障碍物点云
    

2. Quick Start

2.1 Setup Environment

  • Ubuntu 22.04

  • ROS: Humble

  • 配套仿真包(Option):rmu_gazebo_simulator

  • Install small_icp:

    sudo apt install -y libeigen3-dev libomp-dev
    
    git clone https://github.com/koide3/small_gicp.git
    cd small_gicp
    mkdir build && cd build
    cmake .. -DCMAKE_BUILD_TYPE=Release && make -j
    sudo make install

2.2 Create Workspace

mkdir -p ~/ros_ws
cd ~/ros_ws
git clone --recursive https://github.com/SMBU-PolarBear-Robotics-Team/pb2025_sentry_nav.git src/pb2025_sentry_nav

下载先验点云:

先验点云用于 point_lio 和 small_gicp,由于点云文件体积较大,故不存储在 git 中,请前往 FlowUs 下载。

当前 point_lio with prior_pcd 在大场景的效果并不好,比不带先验点云更容易飘,待 Debug 优化

2.3 Build

rosdep install -r --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y
colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release

Note

推荐使用 --symlink-install 选项来构建你的工作空间,因为 pb2025_sentry_nav 广泛使用了 launch.py 文件和 YAML 文件。这个构建参数会为那些非编译的源文件使用符号链接,这意味着当你调整参数文件时,不需要反复重建,只需要重新启动即可。

2.4 Running

可使用以下命令启动,在 RViz 中使用 Nav2 Goal 插件发布目标点。

2.4.1 仿真

单机器人 :

ros2 launch pb2025_nav_bringup rm_sentry_simulation_launch.py \
world:=rmuc_2025 \
slam:=False

多机器人 (实验性功能) :

当前指定的初始位姿实际上是无效的。TODO: 加入 map -> odom 的变换和初始化

ros2 launch pb2025_nav_bringup rm_multi_sentry_simulation_launch.py \
world:=rmul_2024 \
robots:=" \
red_standard_robot1={x: 0.0, y: 0.0, yaw: 0.0}; \
blue_standard_robot1={x: 5.6, y: 1.4, yaw: 3.14}; \
"

2.4.2 实车

注意修改 world 参数为实际地图的名称

ros2 launch pb2025_nav_bringup rm_sentry_reality_launch.py \
world:=<YOUR_WORLD_NAME> \
slam:=False \
use_robot_state_pub:=True

2.5 Launch Arguments

启动参数在仿真和实车中大部分是通用的。以下是所有启动参数表格的图例。

符号 含义
🤖 适用于实车
🖥️ 适用于仿真
可用性 参数 描述 类型 默认值
🤖 🖥️ namespace 顶级命名空间 string "red_standard_robot1"
🤖🖥️ use_sim_time 如果为 True,则使用仿真(Gazebo)时钟 bool 仿真: True; 实车: False
🤖 🖥️ slam 是否启用建图模式。如果为 True,则禁用 small_gicp 并发送静态 tf(map->odom)。然后自动保存 pcd 文件到 ./point_lio/PCD/ bool False
🤖 🖥️ world 在仿真模式,可用选项为 rmul_2024rmuc_2024rmul_2025rmuc_2025 string "rmuc_2025"
在实车模式,world 参数名称与栅格地图和先验点云图的文件名称相同 string ""
🤖 🖥️ map 要加载的地图文件的完整路径。默认路径自动基于 world 参数构建 string 仿真: rmuc_2025.yaml; 实车: 自动填充
🤖 🖥️ prior_pcd_file 要加载的先验 pcd 文件的完整路径。默认路径自动基于 world 参数构建 string 仿真: rmuc_2025.pcd; 实车: 自动填充
🤖 🖥️ params_file 用于所有启动节点的 ROS2 参数文件的完整路径 string 仿真: nav2_params.yaml; 实车: nav2_params.yaml
🤖🖥️ rviz_config_file 要使用的 RViz 配置文件的完整路径 string nav2_default_view.rviz
🤖 🖥️ autostart 自动启动 nav2 栈 bool True
🤖 🖥️ use_composition 是否使用 Composable Node 形式启动 bool True
🤖 🖥️ use_respawn 如果节点崩溃,是否重新启动。本参数仅 use_composition:=False 时有效 bool False
🤖🖥️ use_rviz 是否启动 RViz bool True
🤖 use_robot_state_pub 是 是否使用 robot_state_publisher 发布机器人的 TF 信息
1. 在仿真中,由于支持的 Gazebo 仿真器已经发布了机器人的 TF 信息,因此不需要再次发布。
2. 在实车中,推荐使用独立的包发布机器人的 TF 信息。例如,gimbal_yawgimbal_pitch 关节位姿由串口模块 standard_robot_pp_ros2 提供,此时应将 use_robot_state_pub 设置为 False。
如果没有完整的机器人系统或仅测试导航模块(此仓库)时,可将 use_robot_state_pub 设置为 True。此时,导航模块将发布静态的机器人关节位姿数据以维护 TF 树。
注意:需额外克隆并编译 pb2025_robot_description
bool False

Tip

关于本项目更多细节与实车部署指南,请前往 Wiki

2.6 手柄控制

默认情况下,PS4 手柄控制已开启。键位映射关系详见 nav2_params.yaml 中的 teleop_twist_joy_node 部分。

teleop_twist_joy.gif

TODO