mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: avoid use of AP_Logger.h in library headers
this pulls in many more headers, we should avoid using it whereever we can
This commit is contained in:
parent
4e623bd384
commit
90af3043bc
|
@ -18,6 +18,7 @@
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include "AP_MotorsHeli_RSC.h"
|
#include "AP_MotorsHeli_RSC.h"
|
||||||
#include <AP_RPM/AP_RPM.h>
|
#include <AP_RPM/AP_RPM.h>
|
||||||
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
|
|
@ -4,7 +4,7 @@
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
// default main rotor speed (ch8 out) as a number from 0 ~ 100
|
// default main rotor speed (ch8 out) as a number from 0 ~ 100
|
||||||
#define AP_MOTORS_HELI_RSC_SETPOINT 70
|
#define AP_MOTORS_HELI_RSC_SETPOINT 70
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
#include "AP_MotorsHeli_Swash.h"
|
#include "AP_MotorsHeli_Swash.h"
|
||||||
|
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
// swashplate types
|
// swashplate types
|
||||||
enum SwashPlateType {
|
enum SwashPlateType {
|
||||||
|
|
Loading…
Reference in New Issue