GCS_MAVLink: make sending of send_pid_tuning up

This commit is contained in:
Peter Barker 2019-03-01 10:24:13 +11:00 committed by Andrew Tridgell
parent 8c35ddc0eb
commit 74702b8688
4 changed files with 8 additions and 0 deletions

View File

@ -196,6 +196,7 @@ public:
virtual void send_rangefinder() const;
void send_proximity() const;
virtual void send_nav_controller_output() const = 0;
virtual void send_pid_tuning() = 0;
void send_ahrs2();
void send_ahrs3();
void send_system_time();

View File

@ -4137,6 +4137,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_ahrs3();
break;
case MSG_PID_TUNING:
CHECK_PAYLOAD_SIZE(PID_TUNING);
send_pid_tuning();
break;
case MSG_NAV_CONTROLLER_OUTPUT:
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
send_nav_controller_output();

View File

@ -37,6 +37,7 @@ protected:
bool set_home(const Location& loc, bool lock) override { return false; }
void send_nav_controller_output() const override {};
void send_pid_tuning() override {};
};
/*

View File

@ -39,6 +39,7 @@ protected:
uint32_t custom_mode() const override { return 3; } // magic number
MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
void send_nav_controller_output() const override {};
void send_pid_tuning() override {};
bool set_home_to_current_location(bool lock) override { return false; }
bool set_home(const Location& loc, bool lock) override { return false; }