if the IOMCU resets twice in quick succession then the code that
restores the safety state while flying can fail, leading to the
aircraft trying to continue flying with safety on
This results from two issues:
- a race in handling the last_safety_off variable
- the fact that plane sets the soft_armed state based on safety state
Failing due to being out of time meant we wouldn't incremement the counter, even though we'd emitted the item.
it is important we try to send something, so move this check to be after we increment whichever counter we are using.
RemoteID modules are required to set EMERGENCY status on uncontrolled
descent or crash. This fixes our implementation to do that, either via
existing vehicle crash checking code or via a parachute release
this fixes a regression from 4.2 to 4.3.
previously we automatically set the diagnoals to 1,1,1 if they were
0,0,0. We don't do that any more. I was helping a user who had copied
an old config with 0,0,0 for diagonals and did not understand two
things:
- the compass did not work in 4.3
- large vehicle mag cal didn't work
this caused ftp downloads to intermittently fail. The cause is the FTP
client may ask for a session terminate and then immediately afterwards
a ftp open. The open would fail as the ftp session was considered
active
this ensures the compiler doesn't assume that new always returns a
non-NULL value. Without this the compiler may remove the error path in
code like this:
```
MyObject *x = new MyObject;
if (x == nullptr) {
::printf("Alloc failed\n");
}
```
the reason it can do this is the new operator is marked as throwing an
exception on failure, which means the error path is unreachable. As we
don't have C++ exceptions in ArduPilot could (and do!) have code that
ends up losing protection against allocation failures
Move get_link_rate() and get_protocol_string() to CRSF protocol
allow ELRS at 420kbaud to be configured
allow CRSF to bootstrap at ELRS desired baudrate