Rover: create persist_streamrates() callback to indicate persistence

This commit is contained in:
Peter Barker 2018-05-21 22:34:58 +10:00 committed by Andrew Tridgell
parent d8871078ff
commit 829d18874e
2 changed files with 2 additions and 6 deletions

View File

@ -509,12 +509,6 @@ void GCS_MAVLINK_Rover::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 packet
mavlink_command_int_t packet;

View File

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