Plane: create persist_streamrates() callback to indicate persistence

This commit is contained in:
Peter Barker 2018-05-21 22:35:28 +10:00 committed by Andrew Tridgell
parent 7c98082389
commit 5a087ee7e2
2 changed files with 2 additions and 6 deletions

View File

@ -763,12 +763,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
{
switch (msg->msgid) {
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
{
handle_request_data_stream(msg, true);
break;
}
case MAVLINK_MSG_ID_COMMAND_INT:
{
// decode

View File

@ -39,6 +39,8 @@ protected:
void send_attitude() const override;
void send_simstate() const override;
bool persist_streamrates() const override { return true; }
private:
void handleMessage(mavlink_message_t * msg) override;