Plane: move accept_packet to GCS_MAVLink base class

This commit is contained in:
Peter Barker 2018-12-14 10:12:52 +11:00 committed by Peter Barker
parent 0e6efd6de0
commit 9d323b4b90
2 changed files with 5 additions and 16 deletions

View File

@ -409,6 +409,10 @@ uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const
{
return plane.g.sysid_my_gcs;
}
bool GCS_MAVLINK_Plane::sysid_enforce() const
{
return plane.g2.sysid_enforce;
}
uint32_t GCS_MAVLINK_Plane::telem_delay() const
{
@ -1497,20 +1501,6 @@ void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
gcs().send_airspeed_calibration(vg);
}
/*
return true if we will accept this packet. Used to implement SYSID_ENFORCE
*/
bool GCS_MAVLINK_Plane::accept_packet(const mavlink_status_t &status, mavlink_message_t &msg)
{
if (!plane.g2.sysid_enforce) {
return true;
}
if (msg.msgid == MAVLINK_MSG_ID_RADIO || msg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
return true;
}
return (msg.sysid == plane.g.sysid_my_gcs);
}
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
{
plane.auto_state.next_wp_crosstrack = false;

View File

@ -14,14 +14,13 @@ protected:
uint32_t telem_delay() const override;
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_Rally *get_rally() const override;
uint8_t sysid_my_gcs() const override;
bool sysid_enforce() const override;
bool set_mode(uint8_t mode) override;
bool should_disable_overrides_on_reboot() const override;