From f59412ba65db90e98314fca3a224678ad0604e76 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Beat=20K=C3=BCng?= <beat-kueng@gmx.net>
Date: Mon, 25 Jun 2018 11:06:39 +0200
Subject: [PATCH] mavlink: only enable HIL_ACTUATOR_CONTROLS in hil if link has
 enough bandwidth

Plus correct return value.
Iridium links are below that.
---
 src/modules/mavlink/mavlink_main.cpp | 11 ++++-------
 1 file changed, 4 insertions(+), 7 deletions(-)

diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index b2e2dd2809..d9eb000112 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -859,19 +859,16 @@ Mavlink::set_hil_enabled(bool hil_enabled)
 {
 	int ret = OK;
 
-	/* enable HIL */
-	if (hil_enabled && !_hil_enabled && (_mode != MAVLINK_MODE_IRIDIUM)) {
+	/* enable HIL (only on links with sufficient bandwidth) */
+	if (hil_enabled && !_hil_enabled && _datarate > 5000) {
 		_hil_enabled = true;
-		configure_stream("HIL_ACTUATOR_CONTROLS", 200.0f);
+		ret = configure_stream("HIL_ACTUATOR_CONTROLS", 200.0f);
 	}
 
 	/* disable HIL */
 	if (!hil_enabled && _hil_enabled) {
 		_hil_enabled = false;
-		configure_stream("HIL_ACTUATOR_CONTROLS", 0.0f);
-
-	} else {
-		ret = PX4_ERROR;
+		ret = configure_stream("HIL_ACTUATOR_CONTROLS", 0.0f);
 	}
 
 	return ret;
-- 
GitLab