From 7b573fa2c4339a75602179a38a6100496aa06b99 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Sun, 19 Jun 2022 11:22:02 +0530 Subject: [PATCH] Rover: handle landing target mavlink message --- Rover/GCS_Mavlink.cpp | 9 +++++++++ Rover/GCS_Mavlink.h | 1 + 2 files changed, 10 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index c9bc1aa255..f5030a7d78 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -1072,6 +1072,15 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg) handle_radio_status(msg, rover.should_log(MASK_LOG_PM)); } +/* + handle a LANDING_TARGET command. The timestamp has been jitter corrected +*/ +void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) +{ +#if PRECISION_LANDING == ENABLED + rover.precland.handle_msg(packet, timestamp_ms); +#endif +} uint64_t GCS_MAVLINK_Rover::capabilities() const { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 2b900f2f6d..dab366b730 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -42,6 +42,7 @@ private: void handle_set_position_target_local_ned(const mavlink_message_t &msg); void handle_set_position_target_global_int(const mavlink_message_t &msg); void handle_radio(const mavlink_message_t &msg); + void handle_landing_target(const mavlink_landing_target_t &msg, uint32_t timestamp_ms) override; void send_servo_out();