We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent a4bd033 commit 55f7b14Copy full SHA for 55f7b14
1 file changed
radio/app/drone.py
@@ -157,6 +157,19 @@ def __init__(
157
self._setCancelledConnectionErrorAndCloseMaster()
158
return
159
160
+ try:
161
+ self.master.mav.heartbeat_send(
162
+ mavutil.mavlink.MAV_TYPE_GCS,
163
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
164
+ 0,
165
166
+ mavutil.mavlink.MAV_STATE_ACTIVE,
167
+ )
168
+ except Exception as e:
169
+ self.logger.warning(
170
+ f"Failed to send initial outgoing heartbeat: {e}", exc_info=True
171
172
+
173
try:
174
initial_heartbeat = None
175
heartbeat_timeout_secs = 5.0
0 commit comments