mirror of https://github.com/ArduPilot/ardupilot
Rover: handle RADIO_STATUS is GCS base class
This commit is contained in:
parent
81b279758d
commit
75dec6fcc7
|
@ -793,11 +793,6 @@ void GCS_MAVLINK_Rover::handle_message(const mavlink_message_t &msg)
|
|||
handle_set_position_target_global_int(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_RADIO:
|
||||
case MAVLINK_MSG_ID_RADIO_STATUS:
|
||||
handle_radio(msg);
|
||||
break;
|
||||
|
||||
default:
|
||||
GCS_MAVLINK::handle_message(msg);
|
||||
break;
|
||||
|
@ -1063,15 +1058,6 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
|
|||
}
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
||||
#else
|
||||
handle_radio_status(msg, false);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
handle a LANDING_TARGET command. The timestamp has been jitter corrected
|
||||
*/
|
||||
|
|
|
@ -7,6 +7,8 @@
|
|||
#define AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED 1
|
||||
#endif
|
||||
|
||||
#include "defines.h"
|
||||
|
||||
class GCS_MAVLINK_Rover : public GCS_MAVLINK
|
||||
{
|
||||
public:
|
||||
|
@ -36,6 +38,10 @@ protected:
|
|||
void send_nav_controller_output() const override;
|
||||
void send_pid_tuning() override;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
|
||||
#endif
|
||||
|
||||
private:
|
||||
|
||||
void handle_message(const mavlink_message_t &msg) override;
|
||||
|
|
Loading…
Reference in New Issue