mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_GPS: fixed build on non-PX4 platforms
This commit is contained in:
parent
e69582aa1c
commit
d3b087d2c1
@ -145,20 +145,23 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||||||
AP_GPS_Backend *new_gps = NULL;
|
AP_GPS_Backend *new_gps = NULL;
|
||||||
AP_HAL::UARTDriver *port = instance==0?hal.uartB:hal.uartE;
|
AP_HAL::UARTDriver *port = instance==0?hal.uartB:hal.uartE;
|
||||||
struct detect_state *dstate = &detect_state[instance];
|
struct detect_state *dstate = &detect_state[instance];
|
||||||
|
uint32_t now = hal.scheduler->millis();
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
if (_type[instance] == GPS_TYPE_PX4) {
|
if (_type[instance] == GPS_TYPE_PX4) {
|
||||||
// check for explicitely chosen PX4 GPS beforehand
|
// check for explicitely chosen PX4 GPS beforehand
|
||||||
// it is not possible to autodetect it, nor does it require a real UART
|
// it is not possible to autodetect it, nor does it require a real UART
|
||||||
hal.console->print_P(PSTR(" PX4 "));
|
hal.console->print_P(PSTR(" PX4 "));
|
||||||
new_gps = new AP_GPS_PX4(*this, state[instance], port);
|
new_gps = new AP_GPS_PX4(*this, state[instance], port);
|
||||||
|
goto found_gps;
|
||||||
}
|
}
|
||||||
else if (port == NULL) {
|
#endif
|
||||||
|
|
||||||
|
if (port == NULL) {
|
||||||
// UART not available
|
// UART not available
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t now = hal.scheduler->millis();
|
|
||||||
|
|
||||||
state[instance].instance = instance;
|
state[instance].instance = instance;
|
||||||
state[instance].status = NO_GPS;
|
state[instance].status = NO_GPS;
|
||||||
|
|
||||||
@ -233,6 +236,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
found_gps:
|
||||||
if (new_gps != NULL) {
|
if (new_gps != NULL) {
|
||||||
state[instance].status = NO_FIX;
|
state[instance].status = NO_FIX;
|
||||||
drivers[instance] = new_gps;
|
drivers[instance] = new_gps;
|
||||||
|
@ -22,7 +22,10 @@
|
|||||||
//
|
//
|
||||||
// Code by Holger Steinhaus
|
// Code by Holger Steinhaus
|
||||||
|
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
#include "AP_GPS_PX4.h"
|
#include "AP_GPS_PX4.h"
|
||||||
|
|
||||||
#include <uORB/uORB.h>
|
#include <uORB/uORB.h>
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
@ -76,3 +79,4 @@ AP_GPS_PX4::read(void)
|
|||||||
|
|
||||||
return updated;
|
return updated;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
@ -23,6 +23,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
#include <modules/uORB/topics/vehicle_gps_position.h>
|
#include <modules/uORB/topics/vehicle_gps_position.h>
|
||||||
|
|
||||||
class AP_GPS_PX4 : public AP_GPS_Backend {
|
class AP_GPS_PX4 : public AP_GPS_Backend {
|
||||||
@ -35,5 +36,6 @@ private:
|
|||||||
int _gps_sub;
|
int _gps_sub;
|
||||||
struct vehicle_gps_position_s _gps_pos;
|
struct vehicle_gps_position_s _gps_pos;
|
||||||
};
|
};
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
#endif // AP_GPS_PX4_H
|
||||||
|
|
||||||
#endif // AP_GPS_SIRF_h
|
|
||||||
|
Loading…
Reference in New Issue
Block a user