mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: handle RADIO_STATUS is GCS base class
This commit is contained in:
parent
4c2cc511e6
commit
57535b538e
|
@ -1227,17 +1227,6 @@ void GCS_MAVLINK_Plane::handle_message(const mavlink_message_t &msg)
|
|||
{
|
||||
switch (msg.msgid) {
|
||||
|
||||
case MAVLINK_MSG_ID_RADIO:
|
||||
case MAVLINK_MSG_ID_RADIO_STATUS:
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
handle_radio_status(msg, plane.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
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_Airspeed/AP_Airspeed_config.h>
|
||||
#include "quadplane.h"
|
||||
#include "defines.h"
|
||||
|
||||
class GCS_MAVLINK_Plane : public GCS_MAVLINK
|
||||
{
|
||||
|
@ -18,6 +19,10 @@ protected:
|
|||
|
||||
uint32_t telem_delay() const override;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
|
||||
#endif
|
||||
|
||||
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
|
||||
void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) override;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue