AP_GPS: tidy mavlink message handling using switch statement

This commit is contained in:
Peter Barker 2017-07-26 10:19:37 +10:00 committed by Francisco Ferreira
parent f272c7b6bf
commit e7ff5107fb
1 changed files with 13 additions and 10 deletions

View File

@ -751,20 +751,23 @@ void AP_GPS::handle_gps_inject(const mavlink_message_t *msg)
*/
void AP_GPS::handle_msg(const mavlink_message_t *msg)
{
if (msg->msgid == MAVLINK_MSG_ID_GPS_RTCM_DATA) {
switch (msg->msgid) {
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
// pass data to de-fragmenter
handle_gps_rtcm_data(msg);
return;
}
if (msg->msgid == MAVLINK_MSG_ID_GPS_INJECT_DATA) {
break;
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
handle_gps_inject(msg);
return;
}
uint8_t i;
for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
drivers[i]->handle_msg(msg);
break;
default: {
uint8_t i;
for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && (_type[i] != GPS_TYPE_NONE)) {
drivers[i]->handle_msg(msg);
}
}
break;
}
}
}