GCS_MAVLink: correct return type on get_stream_slowdown_ms
Only used in one place. On slow links may have caused us to re-request a waypoint too often. "Too often" is still >1s intervals.
This commit is contained in:
parent
0b756547be
commit
ca7fcc093c
@ -292,7 +292,7 @@ public:
|
||||
static const struct stream_entries all_stream_entries[];
|
||||
|
||||
virtual uint64_t capabilities() const;
|
||||
uint8_t get_stream_slowdown_ms() const { return stream_slowdown_ms; }
|
||||
uint16_t get_stream_slowdown_ms() const { return stream_slowdown_ms; }
|
||||
|
||||
MAV_RESULT set_message_interval(uint32_t msg_id, int32_t interval_us);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user