Skip to content

Commit c987d57

Browse files
GCS_MAVLink: Add FLIGHT_INFORMATION message
1 parent 833ac8a commit c987d57

File tree

3 files changed

+56
-0
lines changed

3 files changed

+56
-0
lines changed

libraries/GCS_MAVLink/GCS.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -401,6 +401,13 @@ class GCS_MAVLINK
401401
void send_uavionix_adsb_out_status() const;
402402
void send_autopilot_state_for_gimbal_device() const;
403403

404+
struct {
405+
MAV_LANDED_STATE last_landed_state;
406+
uint32_t takeoff_time_ms;
407+
} flight_info;
408+
409+
void send_flight_information();
410+
404411
// lock a channel, preventing use by MAVLink
405412
void lock(bool _lock) {
406413
_locked = _lock;

libraries/GCS_MAVLink/GCS_Common.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5872,6 +5872,49 @@ void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const
58725872
#endif // AP_AHRS_ENABLED
58735873
}
58745874

5875+
void GCS_MAVLINK::send_flight_information()
5876+
{
5877+
const uint32_t time_boot_ms = AP_HAL::millis();
5878+
5879+
// We send time since boot (in micros) rather than a UTC timestamp, as this
5880+
// works better with SITL when SIM_SPEEDUP > 1
5881+
const uint64_t arm_time_us = (uint64_t)AP::arming().arm_time_ms() * AP_USEC_PER_MSEC;
5882+
5883+
const MAV_LANDED_STATE current_landed_state = landed_state();
5884+
if (flight_info.last_landed_state != current_landed_state) {
5885+
switch (current_landed_state) {
5886+
case MAV_LANDED_STATE_IN_AIR:
5887+
case MAV_LANDED_STATE_TAKEOFF:
5888+
case MAV_LANDED_STATE_LANDING: {
5889+
if (!flight_info.takeoff_time_ms) {
5890+
flight_info.takeoff_time_ms = time_boot_ms;
5891+
}
5892+
break;
5893+
}
5894+
default: {
5895+
flight_info.takeoff_time_ms = 0;
5896+
break;
5897+
}
5898+
}
5899+
5900+
flight_info.last_landed_state = current_landed_state;
5901+
}
5902+
5903+
// We send time since boot (in micros) rather than a UTC timestamp, as this
5904+
// works better with SITL when SIM_SPEEDUP > 1
5905+
uint64_t takeoff_time_us = ((uint64_t)flight_info.takeoff_time_ms) * AP_USEC_PER_MSEC;
5906+
5907+
const uint64_t flight_uuid = 0;
5908+
5909+
mavlink_msg_flight_information_send(
5910+
chan,
5911+
time_boot_ms,
5912+
arm_time_us,
5913+
takeoff_time_us,
5914+
flight_uuid
5915+
);
5916+
}
5917+
58755918
void GCS_MAVLINK::send_received_message_deprecation_warning(const char * message)
58765919
{
58775920
// we're not expecting very many of these ever, so a tiny bit of
@@ -6332,6 +6375,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
63326375
break;
63336376
#endif
63346377

6378+
case MSG_FLIGHT_INFORMATION:
6379+
CHECK_PAYLOAD_SIZE(FLIGHT_INFORMATION);
6380+
send_flight_information();
6381+
break;
6382+
63356383
default:
63366384
// try_send_message must always at some stage return true for
63376385
// a message, or we will attempt to infinitely retry the

libraries/GCS_MAVLink/ap_message.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,5 +94,6 @@ enum ap_message : uint8_t {
9494
MSG_HYGROMETER,
9595
MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE,
9696
MSG_RELAY_STATUS,
97+
MSG_FLIGHT_INFORMATION,
9798
MSG_LAST // MSG_LAST must be the last entry in this enum
9899
};

0 commit comments

Comments
 (0)