mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
mavlink: create stream even if rate is 0
This allows to send a message exactly once if requested.
This commit is contained in:
@@ -1266,11 +1266,6 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (interval == 0) {
|
|
||||||
/* stream was not active and is requested to be disabled, do nothing */
|
|
||||||
return OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
// search for stream with specified name in supported streams list
|
// search for stream with specified name in supported streams list
|
||||||
// create new instance if found
|
// create new instance if found
|
||||||
MavlinkStream *stream = create_mavlink_stream(stream_name, this);
|
MavlinkStream *stream = create_mavlink_stream(stream_name, this);
|
||||||
|
|||||||
Reference in New Issue
Block a user