ArduCopter: handle RADIO_STATUS is GCS base class

This commit is contained in:
Peter Barker 2024-01-24 10:57:16 +11:00 committed by Andrew Tridgell
parent 5e5bca2bba
commit 4c2cc511e6
2 changed files with 5 additions and 11 deletions

View File

@ -1485,17 +1485,6 @@ void GCS_MAVLINK_Copter::handle_message(const mavlink_message_t &msg)
}
#endif
case MAVLINK_MSG_ID_RADIO:
case MAVLINK_MSG_ID_RADIO_STATUS: // MAV ID: 109
{
#if HAL_LOGGING_ENABLED
handle_radio_status(msg, copter.should_log(MASK_LOG_PM));
#else
handle_radio_status(msg, false);
#endif
break;
}
case MAVLINK_MSG_ID_TERRAIN_DATA:
case MAVLINK_MSG_ID_TERRAIN_CHECK:
#if AP_TERRAIN_AVAILABLE

View File

@ -2,6 +2,7 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Winch/AP_Winch_config.h>
#include "defines.h"
#ifndef AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
#define AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED 1
@ -57,6 +58,10 @@ protected:
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
#if HAL_LOGGING_ENABLED
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
#endif
private:
// sanity check velocity or acceleration vector components are numbers