DroneMind/voice_drone/tools/publish_flight_intent_ros_once.py
2026-04-14 09:54:26 +08:00

67 lines
2.1 KiB
Python
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

#!/usr/bin/env python3
"""Publish one flight_intent JSON to a ROS1 std_msgs/String topic (for flight bridge).
Run after sourcing ROS, e.g.:
source /opt/ros/noetic/setup.bash && python3 -m voice_drone.tools.publish_flight_intent_ros_once /tmp/intent.json
Or from repo root须在已 source ROS 的 shell 中,且勿覆盖 ROS 的 PYTHONPATH应 prepend:
export PYTHONPATH="$PWD:$PYTHONPATH" && python3 -m voice_drone.tools.publish_flight_intent_ros_once ...
"""
from __future__ import annotations
import argparse
import json
import sys
from pathlib import Path
from typing import Any
import rospy
from std_msgs.msg import String
def _load_payload(path: str | None) -> dict[str, Any]:
if path and path != "-":
raw = Path(path).read_text(encoding="utf-8")
else:
raw = sys.stdin.read()
data = json.loads(raw)
if not isinstance(data, dict):
raise ValueError("root must be a JSON object")
return data
def main() -> None:
ap = argparse.ArgumentParser(description="Publish flight_intent JSON once to ROS String topic")
ap.add_argument(
"json_file",
nargs="?",
default="-",
help="Path to JSON file, or - for stdin (default: stdin)",
)
ap.add_argument("--topic", default="/input", help="ROS topic (default: /input)")
ap.add_argument(
"--wait-subscribers",
type=float,
default=0.0,
help="Seconds to wait for at least one subscriber (default: 0)",
)
args = ap.parse_args()
payload = _load_payload(args.json_file if args.json_file != "-" else None)
json_str = json.dumps(payload, ensure_ascii=False, separators=(",", ":"))
rospy.init_node("flight_intent_ros_publisher_once", anonymous=True)
pub = rospy.Publisher(args.topic, String, queue_size=1, latch=False)
deadline = rospy.Time.now() + rospy.Duration(args.wait_subscribers)
while args.wait_subscribers > 0 and pub.get_num_connections() < 1 and not rospy.is_shutdown():
if rospy.Time.now() > deadline:
break
rospy.sleep(0.05)
rospy.sleep(0.15)
pub.publish(String(data=json_str))
rospy.sleep(0.25)
if __name__ == "__main__":
main()