AP_Baro: reduce header scope

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
This commit is contained in:
Lucas De Marchi 2015-12-01 14:07:15 -02:00 committed by Andrew Tridgell
parent 30f631de8f
commit 81a298c9c8
12 changed files with 26 additions and 52 deletions

View File

@ -18,11 +18,16 @@
* APM_Baro.cpp - barometer driver
*
*/
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
#include "AP_Baro.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_Baro_BMP085.h"
#include "AP_Baro_HIL.h"
#include "AP_Baro_MS5611.h"
#include "AP_Baro_PX4.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,7 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_BARO_H__
#define __AP_BARO_H__
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
@ -160,14 +158,6 @@ private:
// when did we last notify the GCS of new pressure reference?
uint32_t _last_notify_ms;
void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta);
};
#include "AP_Baro_Backend.h"
#include "AP_Baro_MS5611.h"
#include "AP_Baro_BMP085.h"
#include "AP_Baro_HIL.h"
#include "AP_Baro_PX4.h"
#endif // __AP_BARO_H__

View File

@ -19,11 +19,10 @@
Substantially modified by Andrew Tridgell
*/
#include "AP_Baro_BMP085.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "AP_Baro.h"
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;

View File

@ -1,8 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_BARO_BMP085_H__
#define __AP_BARO_BMP085_H__
#pragma once
#include "AP_Baro.h"
#include "AP_Baro_Backend.h"
class AP_Baro_BMP085 : public AP_Baro_Backend
{
@ -23,7 +22,7 @@ private:
// Flymaple has no EOC pin, so use times instead
uint32_t _last_press_read_command_time;
uint32_t _last_temp_read_command_time;
// State machine
uint8_t BMP085_State;
@ -41,5 +40,3 @@ private:
void ReadTemp();
void Calculate();
};
#endif // __AP_BARO_BMP085_H__

View File

@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "AP_Baro.h"
#include "AP_Baro_Backend.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,7 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_BARO_BACKEND_H__
#define __AP_BARO_BACKEND_H__
#pragma once
#include "AP_Baro.h"
@ -25,5 +23,3 @@ protected:
void _copy_to_frontend(uint8_t instance, float pressure, float temperature);
};
#endif // __AP_BARO_BACKEND_H__

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "AP_Baro_HIL.h"
#include "AP_Baro.h"
#include <AP_HAL/AP_HAL.h>
extern const AP_HAL::HAL& hal;

View File

@ -3,11 +3,9 @@
dummy backend for HIL (and SITL). This doesn't actually need to do
any work, as setHIL() is in the frontend
*/
#pragma once
#ifndef __AP_BARO_HIL_H__
#define __AP_BARO_HIL_H__
#include "AP_Baro.h"
#include "AP_Baro_Backend.h"
class AP_Baro_HIL : public AP_Baro_Backend
{
@ -18,5 +16,3 @@ public:
private:
uint8_t _instance;
};
#endif // __AP_BARO_HIL_H__

View File

@ -19,9 +19,9 @@
Heavily modified by Andrew Tridgell
*/
#include "AP_Baro_MS5611.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_Baro.h"
extern const AP_HAL::HAL& hal;

View File

@ -1,10 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#ifndef __AP_BARO_MS5611_H__
#define __AP_BARO_MS5611_H__
#include "AP_Baro_Backend.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_Baro.h"
/** Abstract serial bus device driver for I2C/SPI. */
class AP_SerialBus
@ -128,4 +127,3 @@ private:
void _calculate();
bool _read_prom(uint16_t prom[8]) override;
};
#endif // __AP_BARO_MS5611_H__

View File

@ -1,11 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "AP_Baro_PX4.h"
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include "AP_Baro.h"
#include "AP_Baro_PX4.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>

View File

@ -1,9 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#ifndef __AP_BARO_PX4_H__
#define __AP_BARO_PX4_H__
#include "AP_Baro.h"
#include "AP_Baro_Backend.h"
class AP_Baro_PX4 : public AP_Baro_Backend
{
@ -23,5 +21,3 @@ private:
uint64_t last_timestamp;
} instances[BARO_MAX_INSTANCES];
};
#endif // __AP_BARO_PX4_H__