仍在开发中,更新频率较快且不稳定,不考虑向前兼容。请谨慎使用
深圳北理莫斯科大学 北极熊战队 2025赛季哨兵导航仿真/实车包
rmul_2024 小陀螺 | rmuc_2024 赛博飞坡 + 先验 pcd 里程计 |
---|---|
NAV2 |
---|
本项目基于 NAV2 导航框架 并参考学习了 autonomous_exploration_development_environment 的设计。
-
关于坐标变换:
本项目大幅优化了坐标变换逻辑,考虑雷达原点
lidar_odom
与 底盘原点odom
之间的变换mid360 倾斜侧放在底盘上,使用 point_lio 里程计,small_gicp 重定位,loam_interface 会将 point_lio 输出的
/cloud_registered
从lidar_odom
系转换到odom
系,sensor_scan_generation 将odom
系的点云转换到front_mid360
系,并发布变换odom -> chassis
。 -
关于路径规划:
使用 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 --remap /tf:=/red_standard_robot1/tf --remap /tf_static:=/red_standard_robot1/tf_static
-
LiDAR:
Livox mid360 倾斜侧放在底盘上。
注:仿真环境中,实际上 point pattern 为 velodyne 样式的机械式扫描。此外,由于仿真器中输出的 PointCloud 缺少部分 field,导致 pointlio 无法正常估计状态,故仿真器输出的点云经过 ign_sim_pointcloud_tool 处理添加
time
field。
- Ubuntu 22.04
- ROS: Humble
- Ignition: Fortress
- 配套仿真包:rm_gazebo_simulator
-
安装 Livox SDK2
git clone https://github.com/Livox-SDK/Livox-SDK2.git cd ./Livox-SDK2/ mkdir build cd build cmake .. && make -j sudo make 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
-
克隆仓库
mkdir -p ~/ros_ws/src cd ~/ros_ws/src
git clone --recursive https://github.com/LihanChen2004/pb2025_sentry_nav.git
-
安装依赖
cd ~/ros_ws rosdep install -r --from-paths src --ignore-src --rosdistro $ROS_DISTRO -y
-
下载先验点云
先验点云用于 point_lio 和 small_gicp,由于点云文件体积较大,故不放在 git 中,请前往 FlowUs 下载。
当前 point_lio with prior_pcd 在 rmuc_2024 的效果并不好,比不带先验点云更容易飘,待 debug 优化。可以选择不使用先验点云,只需要到 point_lio.yaml 中将
prior_pcd.enable
设置为False
即可。 -
编译
colcon build --symlink-install --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCMAKE_BUILD_TYPE=Release
后续的开发将基于 Navigation2 进行。
可使用以下命令启动,在 RViz 中使用 Nav2 Goal
插件发布目标点。
-
仿真 - 单机器人
ros2 launch pb2025_nav_bringup rm_sentry_simulation_launch.py \ world:=rmul_2024 \ 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}; \ "
-
实车
注意修改
world
参数为实际地图的名称ros2 launch pb2025_nav_bringup rm_sentry_reality_launch.py \ world:=<YOUR_WORLD_NAME> \ slam:=True
-
world
: 仿真世界名,关联栅格地图与先验点云图的读取。-
仿真时可选项为
rmul_2024
orrmuc_2024
。 -
实车时
world
参数名称与栅格地图与先验点云图的文件名称一致。
-
-
slam
: 若为 True,则为建图模式,否则为有先验信息的导航模式。-
由于没有先验点云图,故禁用 small_gicp_relocalization,发布
map -> odom
静态变换。 -
自动覆写 point_lio 参数
pcd_save.pcd_save_en
为 True,以便保存点云文件。
-
Note
经过一个多月的尝试,考虑到代码的拓展性和可维护性,最终决定放弃 CMU 的导航框架,转而使用 ROS2 的 Navigation2。 但我们保留了 CMU Local Planner 局部路径规划的 demo,仅限雷达放置在 gimbal_yaw 时可正常使用。
可使用以下命令启动,然后在 RViz 中使用 Waypoint
插件发布目标点,或使用 PS3/4 手柄控制机器人。
ros2 launch pb2025_nav_bringup demo_cmu_launch.py \
world:=rmul_2024
默认情况下,PS4 手柄控制已开启。键位映射关系详见 nav2_params.yaml 中的 teleop_twist_joy_node
部分。
左肩键:安全按键,按下后才会发布控制指令到 cmd_vel
右肩键:加速按键,按下后会使速度控制指令变为原先的两倍
左摇杆:发布线速度
右摇杆:发布角速度
-
优化 lidar_odom 和 odom 的关系。目前可以看到机器人底盘实际上是沉在地图下的,雷达与地图高度重合
-
加入 small_gicp 的重定位模块
-
编写实车 launch file 并验证
-
加入 fake_vel_transform,应对云台旋转时,速度参考系变化剧烈的情况
-
优化 pb_omni_pid_pursuit_controller,加入对高曲率路径的速度限制处理
-
加入点云分割,支持动态避障