From 213cdf1a9139488f156721a72feded53d839d964 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 17 Mar 2016 11:01:45 +0000 Subject: [PATCH] mavlink: send out parameters faster over UDP --- src/modules/mavlink/mavlink_main.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 995f10dbc8..48b39d2b2c 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-2016 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 - * @author Julian Oes + * @author Julian Oes * @author Anton Babushkin */ @@ -1871,6 +1871,11 @@ 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);