diff --git a/libraries/AP_Scripting/applets/RockBlock.lua b/libraries/AP_Scripting/applets/RockBlock.lua index 2c5e175b1be1c0..02df3e4fcf59ea 100644 --- a/libraries/AP_Scripting/applets/RockBlock.lua +++ b/libraries/AP_Scripting/applets/RockBlock.lua @@ -10,7 +10,7 @@ Usage: Use the MAVLink High Latency Control ("link hl on|off" in MAVProxy) to control whether to send or not (or use "force_hl_enable") Use the RCK_DEBUG param to view debugging statustexts at the GCS -Use the RCK_FORCEHL param to force-enable high latency mode, instead of enabling from GCS +Use the RCK_FORCEHL param to control the mode of operation: 0=Disabled, 1=Enabled, 2=Enabled on 5000ms telemetry loss Caveats: This will *only* send HIGH_LATENCY2 packets via the SBD modem. No heartbeats, @@ -39,6 +39,9 @@ end port:begin(19200) port:set_flow_control(0) +-- number of millsec that GCS telemetry has been lost for +local link_lost_for = 0 + -- bind a parameter to a variable function bind_param(name) local p = Parameter() @@ -58,7 +61,7 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 4), 'could not add p // @Param: RCK_FORCEHL // @DisplayName: Force enable High Latency mode // @Description: Automatically enables High Latency mode if not already enabled - // @Values: 0:Disabled,1:Enabled + // @Values: 0:Disabled,1:Enabled,2:Enabled on 5000ms telemetry loss // @User: Standard --]] RCK_FORCEHL = bind_add_param('FORCEHL', 1, 0) @@ -91,6 +94,13 @@ RCK_DEBUG = bind_add_param('DEBUG', 3, 0) --]] RCK_ENABLE = bind_add_param('ENABLE', 4, 1) +--[[ +Returns true if the value is NaN, false otherwise +--]] +local function isNaN (x) + return (x ~= x) + end + --[[ Lua Object for decoding and encoding MAVLink (V1 only) messages --]] @@ -102,7 +112,8 @@ local function MAVLinkProcessor() COMMAND_INT = 75, HIGH_LATENCY2 = 235, MISSION_ITEM_INT = 73, - SET_MODE = 11 + SET_MODE = 11, + MISSION_SET_CURRENT = 41 } -- private fields @@ -121,6 +132,7 @@ local function MAVLinkProcessor() _crc_extra[235] = 0xb3 _crc_extra[73] = 0x26 _crc_extra[11] = 0x59 + _crc_extra[41] = 0x1c local _messages = {} _messages[75] = { -- COMMAND_INT @@ -156,6 +168,9 @@ local function MAVLinkProcessor() _messages[11] = { -- SET_MODE { "custom_mode", " 5000 and not gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(true) + elseif link_lost_for < 5000 and gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(false) + end + end -- send HL2 packet every 30 sec, if not aleady in a mailbox check if rockblock.modem_detected and gcs:get_high_latency_status() and diff --git a/libraries/AP_Scripting/applets/RockBlock.md b/libraries/AP_Scripting/applets/RockBlock.md index edd89643da929f..ab6f0f0f395534 100644 --- a/libraries/AP_Scripting/applets/RockBlock.md +++ b/libraries/AP_Scripting/applets/RockBlock.md @@ -26,7 +26,10 @@ The script adds the following parameters: ## RCK_FORCEHL -Automatically enables High Latency mode if not already enabled +Mode of operation: +- 0 = start disabled, can be enabled via MAV_CMD_CONTROL_HIGH_LATENCY +- 1 = start enabled, can be disabled via MAV_CMD_CONTROL_HIGH_LATENCY +- 2 = enabled on loss of telemetry (GCS) link for 5 seconds ## RCK_PERIOD diff --git a/libraries/AP_Scripting/examples/MAVLinkHL.lua b/libraries/AP_Scripting/examples/MAVLinkHL.lua index 21cc968a63ec6a..ec43460ab58590 100644 --- a/libraries/AP_Scripting/examples/MAVLinkHL.lua +++ b/libraries/AP_Scripting/examples/MAVLinkHL.lua @@ -5,9 +5,13 @@ This script requires 1 serial port: A "Script" serial port to connect directly to the GCS Usage: +Use the "hl_mode" variable to control the behaviour of the script: +0 = start enabled, can be disabled via MAV_CMD_CONTROL_HIGH_LATENCY +1 = enabled on loss of telemetry link for 5 seconds (default) +2 = start disabled, can be enabled via MAV_CMD_CONTROL_HIGH_LATENCY + Use the MAVLink High Latency Control ("link hl on|off" in MAVProxy) to control whether to send or not -The script will, however, automatically enable MAVLink High Latency Control upon start Caveats: -This will send HIGH_LATENCY2 packets in place of HEARTBEAT packets @@ -34,8 +38,20 @@ port:set_flow_control(0) local time_last_tx = millis():tofloat() * 0.001 +local hl_mode = 0 +local link_lost_for = 0 + -- enable high latency mode from here, instead of having to enable from GCS -gcs:enable_high_latency_connections(true) +if hl_mode == 0 then + gcs:enable_high_latency_connections(true) +end + +--[[ +Returns true if the value is NaN, false otherwise +--]] +local function isNaN (x) + return (x ~= x) + end --[[ Lua Object for decoding and encoding MAVLink (V1 only) messages @@ -48,7 +64,8 @@ local function MAVLinkProcessor() COMMAND_INT = 75, HIGH_LATENCY2 = 235, MISSION_ITEM_INT = 73, - SET_MODE = 11 + SET_MODE = 11, + MISSION_SET_CURRENT = 41 } -- private fields @@ -67,6 +84,7 @@ local function MAVLinkProcessor() _crc_extra[235] = 0xb3 _crc_extra[73] = 0x26 _crc_extra[11] = 0x59 + _crc_extra[41] = 0x1c local _messages = {} _messages[75] = { -- COMMAND_INT @@ -102,6 +120,9 @@ local function MAVLinkProcessor() _messages[11] = { -- SET_MODE { "custom_mode", " 5000 and not gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(true) + elseif link_lost_for < 5000 and gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(false) + end + end + -- send HL2 packet every 5 sec if gcs:get_high_latency_status() and (millis():tofloat() * 0.001) - time_last_tx > 5 then