4.1 KiB
4.1 KiB
Flight Intent 伴飞桥(ROS 1 + MAVROS)
本目录代码与语音助手 main.py 独立进程:在 MAVROS 已连接 PX4 的前提下,订阅一条 JSON,按 FLIGHT_INTENT_SCHEMA_v1.md 顺序执行。
依赖
- Ubuntu / 设备上已装 ROS Noetic、
mavros(与scripts/run_px4_offboard_one_terminal.sh一致) - Python 能 import:
rospy、std_msgs、geometry_msgs、mavros_msgs - 本仓库根目录
voice_drone_assistant需在PYTHONPATH(启动脚本已设置)
启动
推荐(不会单独敲 roslaunch 时用):一键拉起 roscore(若尚无)→ MAVROS → 伴飞桥:
cd voice_drone_assistant
bash scripts/run_flight_bridge_with_mavros.sh
bash scripts/run_flight_bridge_with_mavros.sh /dev/ttyACM0 921600
已有 MAVROS 时只启桥:
cd voice_drone_assistant
bash scripts/run_flight_intent_bridge_ros1.sh
默认节点名(含 anonymous 后缀):/flight_intent_mavros_bridge_<...>,默认订阅 全局 /input(std_msgs/String,内容为 JSON)。私有参数 ~input_topic 可改(例如专用名时填入完整话题)。桥启动日志会打印实际订阅名。
JSON 格式
- 完整
flight_intent(与云端相同顶层字段),或 - 最小:
{"actions":[...], "summary":"任意非空"}(节点内会补is_flight_intent/version)
校验失败会打 rospy.logerr,不执行。
行为映射(首版)
type |
行为(简述) |
|---|---|
takeoff |
Offboard 位姿:当前点预热 setpoint → OFFBOARD + arm → z0 + Δz(Δz 来自 relative_altitude_m 或参数 ~default_takeoff_relative_m,与 px4_ctrl_offboard_demo 同号约定) |
hover / hold |
当前位姿 hold 约 1s(持续发 setpoint) |
wait |
rospy.Duration,Offboard 时顺带维持当前点 setpoint |
goto |
local_ned / body_ned 增量 → 目标 NED 点,到位容差见 ~goto_position_tolerance |
land |
AUTO.LAND |
return_home |
AUTO.RTL |
注意:真机前请 SITL 验证;不同 PX4/机型的 custom_mode 字符串若不一致需在 ros1_mavros_executor.py 中调整。
参数(私有命名空间)
| 参数 | 默认 | 含义 |
|---|---|---|
~input_topic |
/input |
订阅话题(建议绝对路径;勿再用相对名 input,否则与 /input 对不上) |
~default_takeoff_relative_m |
0.5 |
takeoff 无 relative_altitude_m 时 |
~takeoff_timeout_sec |
15 |
|
~goto_position_tolerance |
0.15 |
m |
~goto_timeout_sec |
60 |
|
~land_timeout_sec |
45 |
land/rtl 等待 disarm 超时 |
~offboard_pre_stream_count |
80 |
与 demo 类似 |
与语音程序的关系
main.py:仍可用 Socket / 本地 offboard 演示脚本(产品过渡期)。- 桥:适合作为 长期 MAVROS 执行端;后续可把语音侧改为 向本节点
input发布 JSON(rospy或roslibpy等),而不再直接起 bash demo。
与语音侧联调:rostopic pub(注意 data:)
std_msgs/String 的 YAML 只有字段 data,JSON 必须写在 data: '...' 里;不能把 JSON 直接当消息顶层(否则会 ERROR: No field name [is_flight_intent] / Args are: [data])。
终端 A:已跑 run_flight_bridge_with_mavros.sh(或 MAVROS + 桥)。
终端 B:
source /opt/ros/noetic/setup.bash
# 订阅名以桥日志为准,常见为全局 /input
rostopic pub -1 /input std_msgs/String \
"data: '{\"is_flight_intent\":true,\"version\":1,\"actions\":[{\"type\":\"land\",\"args\":{}}],\"summary\":\"联调降落\"}'"
悬停 2 秒再降(须已在空中时再试):
rostopic pub -1 /input std_msgs/String \
"data: '{\"is_flight_intent\":true,\"version\":1,\"actions\":[{\"type\":\"hover\",\"args\":{}},{\"type\":\"wait\",\"args\":{\"seconds\":2}},{\"type\":\"land\",\"args\":{}}],\"summary\":\"测\"}'"
在语音进程内集成时,建议 不要在 asyncio 里直接调 rospy,用 独立桥进程 + topic 或 UNIX socket 转发到桥。