AP_GPS: Change search method of GPS type to switch statement.

AP_GPS: Correct the tab code to white space.
This commit is contained in:
murata 2016-12-15 22:12:54 +09:00 committed by Randy Mackay
parent 22fd2025de
commit fd153f2861
1 changed files with 64 additions and 47 deletions

View File

@ -266,30 +266,35 @@ AP_GPS::detect_instance(uint8_t instance)
struct detect_state *dstate = &detect_state[instance];
uint32_t now = AP_HAL::millis();
switch (_type[instance]) {
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
if (_type[instance] == GPS_TYPE_PX4) {
case GPS_TYPE_PX4:
// check for explicitely chosen PX4 GPS beforehand
// it is not possible to autodetect it, nor does it require a real UART
_broadcast_gps_type("PX4", instance, -1); // baud rate isn't valid
new_gps = new AP_GPS_PX4(*this, state[instance], _port[instance]);
goto found_gps;
}
break;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
if (_type[instance] == GPS_TYPE_QURT) {
case GPS_TYPE_QURT:
_broadcast_gps_type("QURTGPS", instance, -1); // baud rate isn't valid
new_gps = new AP_GPS_QURT(*this, state[instance], _port[instance]);
goto found_gps;
}
break;
#endif
// user has to explicitly set the MAV type, do not use AUTO
// do not try to detect the MAV type, assume it's there
if (_type[instance] == GPS_TYPE_MAV) {
case GPS_TYPE_MAV:
_broadcast_gps_type("MAV", instance, -1);
new_gps = new AP_GPS_MAV(*this, state[instance], nullptr);
goto found_gps;
break;
default:
break;
}
if (_port[instance] == nullptr) {
@ -301,16 +306,25 @@ AP_GPS::detect_instance(uint8_t instance)
state[instance].status = NO_GPS;
state[instance].hdop = 9999;
switch (_type[instance]) {
// by default the sbf/trimble gps outputs no data on its port, until configured.
if (_type[instance] == GPS_TYPE_SBF) {
case GPS_TYPE_SBF:
_broadcast_gps_type("SBF", instance, -1); // baud rate isn't valid
new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]);
} else if ((_type[instance] == GPS_TYPE_GSOF)) {
break;
case GPS_TYPE_GSOF:
_broadcast_gps_type("GSOF", instance, -1); // baud rate isn't valid
new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]);
} else if ((_type[instance] == GPS_TYPE_NOVA)) {
break;
case GPS_TYPE_NOVA:
_broadcast_gps_type("NOVA", instance, -1); // baud rate isn't valid
new_gps = new AP_GPS_NOVA(*this, state[instance], _port[instance]);
break;
default:
break;
}
// record the time when we started detection. This is used to try
@ -405,16 +419,18 @@ found_gps:
AP_GPS::GPS_Status
AP_GPS::highest_supported_status(uint8_t instance) const
{
if (drivers[instance] != nullptr)
if (drivers[instance] != nullptr) {
return drivers[instance]->highest_supported_status();
}
return AP_GPS::GPS_OK_FIX_3D;
}
AP_GPS::GPS_Status
AP_GPS::highest_supported_status(void) const
{
if (drivers[primary_instance] != nullptr)
if (drivers[primary_instance] != nullptr) {
return drivers[primary_instance]->highest_supported_status();
}
return AP_GPS::GPS_OK_FIX_3D;
}
@ -634,9 +650,10 @@ AP_GPS::inject_data(uint8_t *data, uint8_t len)
void
AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint8_t len)
{
if (instance < GPS_MAX_INSTANCES && drivers[instance] != nullptr)
if (instance < GPS_MAX_INSTANCES && drivers[instance] != nullptr) {
drivers[instance]->inject_data(data, len);
}
}
void
AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)