the register save must happen before the setjmp() call, which means
outside of the LUAI_TRY() macro. We also should be saving all 32
floating point registers
this is a partial backport of #24132 which fixes RTK injection when
the 1st GPS module is a DroneCAN RTK rover. Without this change RTCM
injection for RTK fix on the base will only work if it happens to come
up as the first module
this fixes an issue where a lua library function triggers an exception
after it does a math operation which changes the floating point
registers on M7 MCUs (such as STM32H7). An example is math.random()
which calls math_random(), which pre-calculates a double value before
checking if the arguments to the call are valid. When it then checks
and finds invalid values the exception longjmp does not restore the
floating point registers.
filter status was initially set to zero then updated. This interacts
with the IMU filtering code which checks filter status from a
different thread to determine active_EKF_type(). When the race
condition is hit then the IMU we are running notch filters on changes
for a single sample, causing a notch filter glitch
if you have a mission item for engine control with delayed start at
height and the engine is already running them it would put the ICE
subsystem into a state where it would no longer start the engine
It was actually 2 bugs:
- an engine control to do a height delayed start should be ignored if
the engine is already running. This prevents an engine control to
start the engine from stopping the engine
- a start_chan high should always try to start the engine
immediately, even if in the wait state
we need to tell the IO firmware that a byte was consumed when we first
detect a protocol as otherwise the next bad byte on DSM will lock us
on the DSM port
this fixes an issue where when you lose R/C input on IOMCU that you
may not regain it when R/C comes back.
The issue stems from us still processing the DSM uart when we are
using the SD3 "SBUS" uart for RC input, and still doing the switch of
the SD3 config every 2 seconds.
When we are not searching for a new protocol we should not be changing
UART config