AP_Compass: don't rebuild tree when single driver changes
Let the drivers be internal to the library so we don't need to rebuild the entire tree when a single driver changes.
This commit is contained in:
parent
d3831dbb98
commit
286697b844
@ -2,8 +2,4 @@
|
|||||||
|
|
||||||
/// @file AP_Compass.h
|
/// @file AP_Compass.h
|
||||||
/// @brief Catch-all header that defines all supported compass classes.
|
/// @brief Catch-all header that defines all supported compass classes.
|
||||||
|
#include "Compass.h"
|
||||||
#include "AP_Compass_HMC5843.h"
|
|
||||||
#include "AP_Compass_HIL.h"
|
|
||||||
#include "AP_Compass_PX4.h"
|
|
||||||
#include "AP_Compass_AK8963.h"
|
|
||||||
|
@ -1,8 +1,17 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include "Compass.h"
|
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
|
|
||||||
|
#include "AP_Compass_AK8963.h"
|
||||||
|
#include "AP_Compass_Backend.h"
|
||||||
|
#include "AP_Compass_HIL.h"
|
||||||
|
#include "AP_Compass_HMC5843.h"
|
||||||
|
#include "AP_Compass_LSM303D.h"
|
||||||
|
#include "AP_Compass_PX4.h"
|
||||||
|
#include "AP_Compass_QURT.h"
|
||||||
|
#include "AP_Compass_qflight.h"
|
||||||
|
#include "AP_Compass.h"
|
||||||
|
|
||||||
extern AP_HAL::HAL& hal;
|
extern AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||||
|
@ -1,14 +1,16 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
||||||
#include "CompassCalibrator.h"
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Declination/AP_Declination.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
|
||||||
#include <AP_Declination/AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_Param/AP_Param.h>
|
||||||
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
|
||||||
|
#include "CompassCalibrator.h"
|
||||||
#include "AP_Compass_Backend.h"
|
#include "AP_Compass_Backend.h"
|
||||||
|
|
||||||
// compass product id
|
// compass product id
|
||||||
@ -410,12 +412,3 @@ private:
|
|||||||
|
|
||||||
AP_Float _calibration_threshold;
|
AP_Float _calibration_threshold;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include "AP_Compass_Backend.h"
|
|
||||||
#include "AP_Compass_HMC5843.h"
|
|
||||||
#include "AP_Compass_HIL.h"
|
|
||||||
#include "AP_Compass_AK8963.h"
|
|
||||||
#include "AP_Compass_PX4.h"
|
|
||||||
#include "AP_Compass_LSM303D.h"
|
|
||||||
#include "AP_Compass_qflight.h"
|
|
||||||
#include "AP_Compass_QURT.h"
|
|
||||||
|
Loading…
Reference in New Issue
Block a user