Skip to content

Commit d31ebcb

Browse files
committed
GCS_Common: add support for sending COMPONENT_INFORMATION
1 parent f63ad01 commit d31ebcb

3 files changed

Lines changed: 25 additions & 1 deletion

File tree

libraries/GCS_MAVLink/GCS.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -405,6 +405,8 @@ class GCS_MAVLINK
405405
void send_flight_information();
406406
#endif
407407

408+
void send_component_information() const;
409+
408410
// lock a channel, preventing use by MAVLink
409411
void lock(bool _lock) {
410412
_locked = _lock;

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1203,7 +1203,8 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
12031203
{ MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR, MSG_AVAILABLE_MODES_MONITOR},
12041204
#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED
12051205
{ MAVLINK_MSG_ID_FLIGHT_INFORMATION, MSG_FLIGHT_INFORMATION},
1206-
#endif
1206+
#endif // AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED
1207+
{ MAVLINK_MSG_ID_COMPONENT_INFORMATION, MSG_COMPONENT_INFORMATION},
12071208
};
12081209

12091210
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
@@ -6335,6 +6336,21 @@ bool GCS_MAVLINK::send_available_mode_monitor()
63356336
return true;
63366337
}
63376338

6339+
void GCS_MAVLINK::send_component_information() const
6340+
{
6341+
const char *general_metadata_url = "mftp:/@SYS/general_metadata.json";
6342+
const uint32_t general_metadata_checksum = 133761337;
6343+
6344+
mavlink_msg_component_information_send(
6345+
chan,
6346+
AP_HAL::millis(),
6347+
general_metadata_checksum,
6348+
general_metadata_url,
6349+
0, // -1?
6350+
""
6351+
);
6352+
}
6353+
63386354
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
63396355
{
63406356
bool ret = true;
@@ -6738,6 +6754,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
67386754
}
67396755
#endif
67406756

6757+
case MSG_COMPONENT_INFORMATION:
6758+
CHECK_PAYLOAD_SIZE(COMPONENT_INFORMATION);
6759+
send_component_information();
6760+
break;
6761+
67416762
#if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED
67426763
case MSG_UAVIONIX_ADSB_OUT_STATUS:
67436764
CHECK_PAYLOAD_SIZE(UAVIONIX_ADSB_OUT_STATUS);

libraries/GCS_MAVLink/ap_message.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,5 +113,6 @@ enum ap_message : uint8_t {
113113
#if AP_MAVLINK_MSG_FLIGHT_INFORMATION_ENABLED
114114
MSG_FLIGHT_INFORMATION = 100,
115115
#endif
116+
MSG_COMPONENT_INFORMATION,
116117
MSG_LAST // MSG_LAST must be the last entry in this enum
117118
};

0 commit comments

Comments
 (0)