|
|
|
@ -1072,6 +1072,15 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
@@ -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 |
|
|
|
|
{ |
|
|
|
|