mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: create persist_streamrates() callback to indicate persistence
This commit is contained in:
parent
d8871078ff
commit
829d18874e
@ -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;
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user