|
|
|
@ -22,8 +22,7 @@ extern const AP_HAL::HAL& hal;
@@ -22,8 +22,7 @@ extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
|
|
// constructor
|
|
|
|
|
AP_Beacon_Pozyx::AP_Beacon_Pozyx(AP_Beacon &frontend, AP_SerialManager &serial_manager) : |
|
|
|
|
AP_Beacon_Backend(frontend), |
|
|
|
|
linebuf_len(0) |
|
|
|
|
AP_Beacon_Backend(frontend) |
|
|
|
|
{ |
|
|
|
|
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Beacon, 0); |
|
|
|
|
if (uart != nullptr) { |
|
|
|
@ -41,12 +40,6 @@ bool AP_Beacon_Pozyx::healthy()
@@ -41,12 +40,6 @@ bool AP_Beacon_Pozyx::healthy()
|
|
|
|
|
// update the state of the sensor
|
|
|
|
|
void AP_Beacon_Pozyx::update(void) |
|
|
|
|
{ |
|
|
|
|
static uint8_t counter = 0; |
|
|
|
|
counter++; |
|
|
|
|
if (counter > 200) { |
|
|
|
|
counter = 0; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (uart == nullptr) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|