mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
81a298c9c8
We don't need to expose to other libraries how each backend is implemented. AP_Baro.h is the main header, included by other libraries. Instead of including each backend in the main header, move them to where they are needed. Additionally standardize the order and how we include the headers. The advantages are: - Internals of each backend is not exposed outside of the library - Faster incremental builds since we don't need to recompile whoever includes AP_Baro.h because a backend changed
26 lines
682 B
C++
26 lines
682 B
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
#pragma once
|
|
|
|
#include "AP_Baro.h"
|
|
|
|
class AP_Baro_Backend
|
|
{
|
|
public:
|
|
AP_Baro_Backend(AP_Baro &baro);
|
|
|
|
// each driver must provide an update method to copy accumulated
|
|
// data to the frontend
|
|
virtual void update() = 0;
|
|
|
|
// accumulate function. This is used for backends that don't use a
|
|
// timer, and need to be called regularly by the main code to
|
|
// trigger them to read the sensor
|
|
virtual void accumulate(void) {}
|
|
|
|
protected:
|
|
// reference to frontend object
|
|
AP_Baro &_frontend;
|
|
|
|
void _copy_to_frontend(uint8_t instance, float pressure, float temperature);
|
|
};
|