fix potential null pointer

This commit is contained in:
Michael Oborne 2012-04-20 17:53:07 +08:00
parent 1478191ecf
commit 8d797fec3c

View File

@ -142,7 +142,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_present |= (1<<2); // compass present
}
control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps->fix) {
if (g_gps != NULL && g_gps->fix) {
control_sensors_present |= (1<<5); // GPS present
}
control_sensors_present |= (1<<10); // 3D angular rate control