Last active
May 31, 2019 12:11
-
-
Save AlexisTM/58105abf31b7254e3c80e52fcee83d67 to your computer and use it in GitHub Desktop.
Minimal heartbeat for a Ground control station in ROS for PX4
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#!/usr/bin/env python2 | |
""" | |
Minimal heartbeat for a Ground control station in ROS for PX4. | |
It enables STATUS_TEXT streams. | |
Author: AlexisTM | |
""" | |
from threading import Thread | |
import rospy | |
from mavros import mavlink | |
from mavros_msgs.msg import Mavlink | |
from pymavlink import mavutil | |
def send_heartbeat(): | |
mavlink_pub = rospy.Publisher('/mavlink/to', Mavlink, queue_size=1) | |
rate = rospy.Rate(2) | |
heartbeat_msg = mavutil.mavlink.MAVLink_heartbeat_message( | |
mavutil.mavlink.MAV_TYPE_GCS, 0, 0, 0, 0, 0) | |
heartbeat_msg.pack(mavutil.mavlink.MAVLink('', 2, 1)) | |
heartbeat_ros = mavlink.convert_to_rosmsg(heartbeat_msg) | |
while not rospy.is_shutdown(): | |
try: | |
mavlink_pub.publish(heartbeat_ros) | |
rate.sleep() | |
except rospy.ROSInterruptException as ex: | |
rospy.logfatal(ex) | |
heartbeat_thread = Thread(target=send_heartbeat, args=()) | |
heartbeat_thread.daemon = True | |
heartbeat_thread.start() |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment