Browse Source

GCS_Mavlink: add AIS msg

gps-1.3.1
Peter Hall 5 years ago committed by Randy Mackay
parent
commit
60db4c1a62
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp
  2. 1
      libraries/GCS_MAVLink/ap_message.h

2
libraries/GCS_MAVLink/GCS_Common.cpp

@ -47,6 +47,7 @@ @@ -47,6 +47,7 @@
#include <AP_Winch/AP_Winch.h>
#include <AP_OSD/AP_OSD.h>
#include <AP_RCTelemetry/AP_CRSF_Telem.h>
#include <AP_AIS/AP_AIS.h>
#include <stdio.h>
@ -851,6 +852,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c @@ -851,6 +852,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_WINCH_STATUS, MSG_WINCH_STATUS},
{ MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH},
{ MAVLINK_MSG_ID_HIGH_LATENCY2, MSG_HIGH_LATENCY2},
{ MAVLINK_MSG_ID_AIS_VESSEL, MSG_AIS_VESSEL},
};
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {

1
libraries/GCS_MAVLink/ap_message.h

@ -79,5 +79,6 @@ enum ap_message : uint8_t { @@ -79,5 +79,6 @@ enum ap_message : uint8_t {
MSG_WINCH_STATUS,
MSG_WATER_DEPTH,
MSG_HIGH_LATENCY2,
MSG_AIS_VESSEL,
MSG_LAST // MSG_LAST must be the last entry in this enum
};

Loading…
Cancel
Save