ardupilot/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h
Lucas De Marchi 9c6bd38e91 AP_InertialSensor: sanitize includes
Due to the way the headers are organized changing a single change in an
inertial sensor driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.

With this patch only AP_InertialSensor/AP_InertialSensor.h is exposed to
most users. There are some corner cases to integrate with some example
code, but most of the places now depend only on this header and this
header doesn't depend on the specific backends.

Now changing a single header, e.g. AP_InertialSensor_L3G4200D.h triggers
a rebuild only of these files:

	$ waf copter
	'copter' finished successfully (0.000s)
	Waf: Entering directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
	[ 80/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor.cpp
	[ 84/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp
	[310/370] Linking build/minlure/ArduCopter/libArduCopter_libs.a
	[370/370] Linking build/minlure/bin/arducopter
	Waf: Leaving directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
2016-02-01 14:18:51 -02:00

37 lines
869 B
C++

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_Backend.h"
class AP_InertialSensor_L3G4200D : public AP_InertialSensor_Backend
{
public:
AP_InertialSensor_L3G4200D(AP_InertialSensor &imu);
~AP_InertialSensor_L3G4200D();
/* update accel and gyro state */
bool update();
// detect the sensor
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);
// return product ID
int16_t product_id() const { return AP_PRODUCT_ID_L3G4200D; }
private:
bool _init_sensor();
void _accumulate();
// gyro and accel instances
uint8_t _gyro_instance;
uint8_t _accel_instance;
};
#endif