4 Star 63 Fork 12

深圳北理莫斯科大学RoboMaster北极熊战队 / PB_RMSimulation

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
克隆/下载
贡献代码
同步代码
取消
提示: 由于 Git 不支持空文件夾,创建文件夹后会生成空的 .keep 文件
Loading...
README
MIT

PB_RM_Simulation

深圳北理莫斯科大学 北极熊战队 哨兵导航仿真包

一. 项目介绍

本项目使用麦克纳姆轮仿真小车,附加 Livox Mid360 雷达与 IMU,在 RMUC/RMUL 地图进行导航算法仿真。

功能演示视频:寒假在家,怎么调车!?更适合新手宝宝的 RM 导航仿真

Gazebo 仿真 Fast_LIO + Navigation2
Gazebo 仿真 Fast_LIO + Navigation2
Mid360点云仿真 + FAST_LIO 里程计 + 障碍物/地面点云分割 + 三维点云转二维 + Navigation2
Gazebo 仿真

二. rm_simulation 话题接口

Topic name Type Note
/livox/lidar livox_ros_driver2/msg/CustomMsg Mid360 自定义消息类型
/livox/lidar/pointcloud sensor_msgs/msg/PointCloud2 ROS2 点云消息类型
/livox/imu sensor_msgs/msg/Imu Gazebo 插件仿真 IMU
/cmd_vel geometry_msgs/msg/Twist 麦克纳姆轮小车运动控制接口

三. 环境配置

当前开发环境为 Ubuntu22.04, ROS2 humble, Gazebo 11.10.0

  1. 安装依赖

    sudo apt install -y ros-humble-gazebo-*
    sudo apt install -y ros-humble-xacro
    sudo apt install -y ros-humble-robot-state-publisher
    sudo apt install -y ros-humble-joint-state-publisher
    sudo apt install -y ros-humble-rviz2
    sudo apt install -y ros-humble-nav2*
    sudo apt install -y ros-humble-slam-toolbox
    sudo apt install -y ros-humble-pcl-ros
    sudo apt install -y ros-humble-pcl-conversions
    sudo apt install -y ros-humble-libpointmatcher
    sudo apt install -y ros-humble-tf2-geometry-msgs
    sudo apt install -y libboost-all-dev
    sudo apt install -y libgoogle-glog-dev

    后续编译与运行过程中如果有依赖功能包未安装,按类似的方法安装。

  2. 安装 Livox SDK2

    sudo apt install cmake
    git clone https://github.com/Livox-SDK/Livox-SDK2.git
    cd ./Livox-SDK2/
    mkdir build
    cd build
    cmake .. && make -j
    sudo make install

四. 编译运行

git clone --recursive https://gitee.com/SMBU-POLARBEAR/pb_rmsimulation --depth=1
cd pb_rmsimulation
./build.sh

可选参数

  1. world:

    (仿真模式)

    (真实环境)

    • 自定,world 等价于 .pcd(ICP使用的点云图) 文件和 .yaml(Nav使用的栅格地图) 的名称,
  2. mode:

    • mapping - 边建图边导航
    • nav - 已知全局地图导航
  3. localization (仅 mode:=nav 时本参数有效)

    • amcl - 使用 AMCL 算法定位(经典算法)
    • slam_toolbox - 使用 slam_toolbox localization 模式定位(动态场景中效果更好)
    • icp - 使用 ICP_Localization 算法定位(性能开销较多)

    Tips:

    1. 若使用 AMCL 算法定位时,启动后需要在 rviz2 中手动给定初始位姿。
    2. 若使用 slam_toolbox 定位,需要提供 .posegraph 地图,详见 localization using SLAM_Toolbox
    3. 若使用 ICP_Localization 定位,需要提供 .pcd 点云图
  4. rviz:

    • True - 可视化 robot_descrition, FAST_LIO
    • False - 仅提供 nav2 可视化窗口

仿真模式

  • 示例:
    • 边建图边导航

      ros2 launch rm_bringup bringup_sim.launch.py \
      world:=RMUL \
      mode:=mapping
    • 已知全局地图导航

      ros2 launch rm_bringup bringup_sim.launch.py \
      world:=RMUL \
      mode:=nav \
      localization:=slam_toolbox

真实环境

  • 示例:
    • 边建图边导航

      ros2 launch rm_bringup bringup_real.launch.py \
      world:=YOUR_WORLD_NAME \
      mode:=mapping

      Tips:

      1. 保存点云 pcd 文件:需先在 fastlio_mid360.yaml 中 将 pcd_save_en 改为 true,并设置 .pcd 文件的名称
      2. 保存栅格地图:需先在 save_grid_map.shYOUR_MAP_NAME 更改为与 .pcd 文件相同的名称。保存后在当前工作空间新开终端,运行 ./save_grid_map.sh 即可
      3. 保存 .posegraph 地图:请参考 localization using SLAM_Toolbox
    • 已知全局地图导航

      ros2 launch rm_bringup bringup_real.launch.py \
      world:=YOUR_WORLD_NAME \
      mode:=nav \
      localization:=slam_toolbox

      Tips: 栅格地图文件和 pcd 文件需命名为相同名称,分别存放至 src/rm_bringup/mapsrc/rm_bringup/PCD 中,启动导航时 world 指定为文件名前缀即可。

小工具 - 键盘控制

ros2 run teleop_twist_keyboard teleop_twist_keyboard

致谢

Mid360 点云仿真:参考了 livox_laser_simulationlivox_laser_simulation_RO2Issue15: CustomMsg

导航算法框架:基于 中南大学 FYT 战队 RM 哨兵上位机算法 略微修改以适配仿真。

非常非常感谢以上开源项目 / Issue 的帮助!!!

常见问题

详见 Issue

MIT License Copyright (c) 2024 ziknagXie Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

简介

ROS2-Gazebo simulation package leveraging Mid360 and FASTLIO for navigation. Contact me (QQ): 757003373 展开 收起
C++ 等 5 种语言
MIT
取消

发行版

暂无发行版

贡献者

全部

近期动态

加载更多
不能加载更多了
C++
1
https://gitee.com/SMBU-POLARBEAR/pb_rmsimulation.git
git@gitee.com:SMBU-POLARBEAR/pb_rmsimulation.git
SMBU-POLARBEAR
pb_rmsimulation
PB_RMSimulation
master

搜索帮助