Copter: move accept_packet to GCS_MAVLink base class
This commit is contained in:
parent
588829161b
commit
0e6efd6de0
@ -244,6 +244,10 @@ uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const
|
||||
{
|
||||
return copter.g.sysid_my_gcs;
|
||||
}
|
||||
bool GCS_MAVLINK_Copter::sysid_enforce() const
|
||||
{
|
||||
return copter.g2.sysid_enforce;
|
||||
}
|
||||
|
||||
uint32_t GCS_MAVLINK_Copter::telem_delay() const
|
||||
{
|
||||
@ -1455,20 +1459,6 @@ void Copter::mavlink_delay_cb()
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
return true if we will accept this packet. Used to implement SYSID_ENFORCE
|
||||
*/
|
||||
bool GCS_MAVLINK_Copter::accept_packet(const mavlink_status_t &status, mavlink_message_t &msg)
|
||||
{
|
||||
if (!copter.g2.sysid_enforce) {
|
||||
return true;
|
||||
}
|
||||
if (msg.msgid == MAVLINK_MSG_ID_RADIO || msg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
|
||||
return true;
|
||||
}
|
||||
return (msg.sysid == copter.g.sysid_my_gcs);
|
||||
}
|
||||
|
||||
AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
|
||||
{
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
|
@ -14,14 +14,13 @@ protected:
|
||||
|
||||
uint32_t telem_delay() const override;
|
||||
|
||||
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
||||
|
||||
AP_Rally *get_rally() const override;
|
||||
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
||||
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
||||
AP_VisualOdom *get_visual_odom() const override;
|
||||
|
||||
uint8_t sysid_my_gcs() const override;
|
||||
bool sysid_enforce() const override;
|
||||
|
||||
bool set_mode(uint8_t mode) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user