ego_planner算法的仿真环境(主要是ros)-算法的解耦实现.

本系列内容主要是深入分析ego_planner算法的实现,并且将核心的算法部分转化为非ros依赖的形式(Cmake项目),实现上我们主要通过共享内存与ros的仿真环境进行数据交换.
项目链接:https://github.com/chan-yuu/ego_planner_standalone.git
如果觉得有用的话不要忘了star哦.

├── application # gui界面,用于快速启动程序
│   └── ego_planner_gui.py
├── docs
│   ├── 1.0
│   ├── png
│   └── scripts
├── ego-planner # ros环境部分,包括感知信息
│   ├── modified_realsense2_camera.zip
│   └── src
├── planner_standalone # 独立的算法模块.
│   ├── build # 编译到build中的可执行文件.
│   ├── CMakeLists.txt
│   ├── include
│   └── src
└── README.md

ego_planner_standalone

本项目将原始的ROS EGO-Planner分离为两部分:

  1. ROS Bridge (ego-planner/src/ros_bridge): 处理ROS消息和共享内存通信
  2. Planner Standalone (planner_standalone): 无ROS依赖的纯C++规划算法

当前架构

数据流

仿真环境 (simulator)
    ↓
ROS话题订阅
    ↓
ROS Bridge Node
    ↓
共享内存 (Shared Memory)
    ↓
Planner Standalone (FSM + 算法)
    ↓
共享内存 (Shared Memory)
    ↓
ROS Bridge Node
    ↓
ROS话题发布 → Traj Server → 控制器

输入数据(从仿真环境)

  1. 定位数据 (/visual_slam/odom)

    • 位置、速度、姿态
    • 频率: ~100Hz
  2. 点云数据 (/grid_map/occupancy_inflate)

    • 已膨胀的障碍物点云
    • 频率: ~10Hz
    • 注意: 仿真已完成膨胀,算法端不需要再处理
  3. 目标航点 (/waypoint_generator/waypoints)

    • 目标位置
    • 事件驱动(用户在RViz中点击)

输出数据(给控制器)

  1. B样条轨迹 (/planning/bspline)

    • 控制点
    • 节点向量 (knots)
    • 轨迹ID
    • 发布给 traj_server
  2. 轨迹可视化 (/planning/bspline_path)

    • Path消息格式
    • 用于RViz显示
  3. 规划器状态 (/planning/planner_state)

    • FSM状态 (INIT, WAIT_TARGET, GEN_NEW_TRAJ, etc.)

算法流程

整个规划器的运行逻辑由 main.cpp 驱动,通过 EGOPlannerManager 协调各个模块。

核心规划层
基础设施层
后端优化循环
1.读取状态/环境
2.提供障碍物距离
路径点
平滑/碰撞/可行性
未收敛
收敛
3.写入轨迹
GridMap: 地图更新
需要重规划?
DynAStar: 前端路径搜索
B-Spline: 轨迹初始化
计算代价 & 梯度
开始优化
L-BFGS: 迭代更新控制点
时间重新分配
main.cpp: 主循环
IOInterface: 共享内存读写
程序启动
PolynomialTrajectory: 生成轨迹

使用方法

pip install pyside6
python application/ego_planner_gui.py

到build界面中,编译两个部分:

编译完成后,就可以直接启动了,其中前面两个大的是总的启动按钮,可以运行四个start

或者按照顺序启动下面的四个start即可.
在这里插入图片描述

对应的命令是:

cd ego-planner;source devel/setup.bash && roslaunch ego_planner_bridge sim_only.launch

cd ego-planner;source devel/setup.bash && roslaunch grid_map_standalone test_grid_map.launch

cd ego-planner;source devel/setup.bash && roslaunch ego_planner_bridge run_bridge.launch

cd planner_standalone/build;./ego_planner_standalone
在使用 XTDrone 的 `ego_planner_node` 进行三维运动规划时,用户可能会遇到有限状态机(FSM)状态卡在 `INIT` 的问题,提示信息如 `[FSM]: state: INIT no odom.wait for goal ...`。这一问题通常与里程计(Odometry)数据的缺失或订阅错误有关。 ### 问题分析 `ego_planner_node` 依赖于来自 MAVROS 的里程计信息,用于初始化状态机并进入后续的运动规划阶段。如果节点未能正确订阅到里程计话题(如 `/iris_0/mavros/odometry/in`),则状态机会一直停留在 `INIT` 状态,等待有效的里程计输入。 根据已有信息,`single_uav.launch` 文件中 `odom_topic` 的值可能配置错误,导致节点订阅了错误的话题路径,例如 `/iris_0/iris_0/mavros/odometry/in`,而正确的话题应为 `/iris_0/mavros/odometry/in` [^1]。 ### 解决方案 #### 1. 修改 `single_uav.launch` 文件中的 `odom_topic` 参数 找到 `ego_planner` 功能包下的 `launch` 文件夹中的 `single_uav.launch` 文件,并修改其中的 `odom_topic` 参数值: ```xml <arg name="odom_topic" value="/iris_0/mavros/odometry/in"/> ``` 确保该值与 MAVROS 发布的里程计话题一致,通常为 `/mavros/odometry/in`,前缀 `/iris_0` 为多无人机仿真中的命名空间。 #### 2. 检查 MAVROS 是否正确发布里程计信息 运行以下命令查看是否发布里程计数据: ```bash rostopic echo /iris_0/mavros/odometry/in ``` 如果没有数据输出,检查 MAVROS 的连接状态、参数配置以及 PX4/Firmware 是否正常运行。 #### 3. 检查 `ego_planner_node` 的订阅状态 使用以下命令确认节点是否成功订阅到里程计话题: ```bash rostopic info /iris_0_ego_planner_node ``` 查看输出中是否包含 `/iris_0/mavros/odometry/in` 的订阅信息。 #### 4. 确保 TF 变换正常 有时 TF 数据缺失也会导致里程计无法被正确解析。运行以下命令检查 TF 树: ```bash rosrun tf view_frames ``` 确保 `/iris_0` 命名空间下的坐标系变换(如 `base_link` 到 `odom`)完整且无错误。 ### 验证修复 启动仿真环境并运行以下命令: ```bash roslaunch ego_planner single_uav.launch ``` 观察 `ego_planner_node` 的日志输出,确认 FSM 是否成功从 `INIT` 转换到 `WAIT_GOAL` 或其他状态。如果问题已解决,应能看到如下信息: ``` [FSM]: state: WAIT_GOAL ``` ### 代码片段示例:`ego_planner_node.cpp` 中状态机初始化逻辑 以下代码片段展示了 FSM 初始化阶段对里程计的依赖: ```cpp if (current_state_ == FSM_STATE::INIT) { if (have_odom_) { current_state_ = FSM_STATE::WAIT_GOAL; ROS_INFO("[FSM]: state: WAIT_GOAL"); } else { ROS_WARN("[FSM]: state: INIT no odom. wait for goal..."); } } ``` 此逻辑表明,只有在接收到有效的里程计数据后,状态机才会从 `INIT` 进入下一阶段 [^2]。 ---
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

白云千载尽

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值