mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 09:28:58 +00:00
Revert "mavlink: send out parameters faster over UDP"
This reverts commit 213cdf1a91.
Raising the stream rate of param values had the nice effect that
receiving the params became really quick. However, on the downside it
set all other streams pretty slow. This needs to be fixed differently.
This commit is contained in:
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -35,7 +35,7 @@
|
||||
* MAVLink 1.0 protocol implementation.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Julian Oes <julian@oes.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Anton Babushkin <anton.babushkin@me.com>
|
||||
*/
|
||||
|
||||
@@ -1891,11 +1891,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
send_autopilot_capabilites();
|
||||
}
|
||||
|
||||
/* send parameters faster over UDP */
|
||||
if (get_protocol() == UDP) {
|
||||
configure_stream("PARAM_VALUE", 100000.0f);
|
||||
}
|
||||
|
||||
while (!_task_should_exit) {
|
||||
/* main loop */
|
||||
usleep(_main_loop_delay);
|
||||
|
||||
Reference in New Issue
Block a user