Bläddra i källkod

Set heartbeat autopilot correctly

According to the documentation, components that are
not autopilots, should set the heartbeat autopilot field
to MAV_AUTOPILOT_INVALID.
https://mavlink.io/en/services/heartbeat.html#component-identity

Signed-off-by: Soren Friis <soren.friis@intel.com>
Soren Friis 3 år sedan
förälder
incheckning
f5758bb05b
1 ändrade filer med 1 tillägg och 1 borttagningar
  1. 1 1
      RemoteIDModule/mavlink.cpp

+ 1 - 1
RemoteIDModule/mavlink.cpp

@@ -62,7 +62,7 @@ void MAVLinkSerial::update_send(void)
         mavlink_msg_heartbeat_send(
             chan,
             MAV_TYPE_ODID,
-            MAV_AUTOPILOT_ARDUPILOTMEGA,
+            MAV_AUTOPILOT_INVALID,
             0,
             0,
             0);