AP_ExternalAHRS: Fix nullptr crash on bootup

* If you didn't set the serial port parameter correctly, but enabled MicroStrain AHRS, it would crash on boot
* This is because AP_AHRS calls update() which calls build_packet()

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
Ryan Friedman 2023-08-27 22:27:46 -06:00 committed by Peter Barker
parent e69760f51b
commit cbc0043b9b

View File

@ -73,6 +73,10 @@ void AP_ExternalAHRS_MicroStrain5::update_thread(void)
// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet.
void AP_ExternalAHRS_MicroStrain5::build_packet()
{
if (uart == nullptr) {
return;
}
WITH_SEMAPHORE(sem);
uint32_t nbytes = MIN(uart->available(), 2048u);
while (nbytes--> 0) {