AP_Mount: prevent SIYI driver crash if serial port not setup

if MNT1_TYPE=8 and no serial protocol set to gimbal then a camera
trigger can crash the vehicle
This commit is contained in:
Andrew Tridgell 2023-07-11 19:56:12 +10:00
parent cc19359c33
commit 787d03c1a3

View File

@ -475,6 +475,9 @@ void AP_Mount_Siyi::process_packet()
// returns true on success, false if outgoing serial buffer is full
bool AP_Mount_Siyi::send_packet(SiyiCommandId cmd_id, const uint8_t* databuff, uint8_t databuff_len)
{
if (!_initialised) {
return false;
}
// calculate and sanity check packet size
const uint16_t packet_size = AP_MOUNT_SIYI_PACKETLEN_MIN + databuff_len;
if (packet_size > AP_MOUNT_SIYI_PACKETLEN_MAX) {