mirror of https://github.com/ArduPilot/ardupilot
AP_EFI: tidy AP_EFI defines
This commit is contained in:
parent
e76462f005
commit
593983df7a
|
@ -94,17 +94,17 @@ void AP_EFI::init(void)
|
|||
backend = new AP_EFI_Serial_Lutan(*this);
|
||||
break;
|
||||
case Type::NWPMU:
|
||||
#if HAL_EFI_NWPWU_ENABLED
|
||||
#if AP_EFI_NWPWU_ENABLED
|
||||
backend = new AP_EFI_NWPMU(*this);
|
||||
#endif
|
||||
break;
|
||||
case Type::DroneCAN:
|
||||
#if HAL_EFI_DRONECAN_ENABLED
|
||||
#if AP_EFI_DRONECAN_ENABLED
|
||||
backend = new AP_EFI_DroneCAN(*this);
|
||||
#endif
|
||||
break;
|
||||
case Type::CurrawongECU:
|
||||
#if HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
#if AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
backend = new AP_EFI_Currawong_ECU(*this);
|
||||
#endif
|
||||
break;
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "AP_EFI_Currawong_ECU.h"
|
||||
|
||||
#if HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
#if AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_PiccoloCAN/piccolo_protocol/ECUPackets.h>
|
||||
|
@ -103,4 +103,4 @@ bool AP_EFI_Currawong_ECU::handle_message(AP_HAL::CANFrame &frame)
|
|||
return valid;
|
||||
}
|
||||
|
||||
#endif // HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
#endif // AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
|
|
|
@ -21,15 +21,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_EFI_config.h"
|
||||
|
||||
#if AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
|
||||
#include "AP_EFI.h"
|
||||
#include "AP_EFI_Backend.h"
|
||||
|
||||
#ifndef HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
#define HAL_EFI_CURRAWONG_ECU_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS && (BOARD_FLASH_SIZE > 1024)
|
||||
#endif
|
||||
|
||||
#if HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
|
||||
class AP_EFI_Currawong_ECU : public AP_EFI_Backend {
|
||||
public:
|
||||
AP_EFI_Currawong_ECU(AP_EFI &_frontend);
|
||||
|
@ -49,5 +47,5 @@ private:
|
|||
friend class AP_PiccoloCAN;
|
||||
};
|
||||
|
||||
#endif // HAL_EFI_CURRAWONG_ECU_ENABLED
|
||||
#endif // AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include "AP_EFI_DroneCAN.h"
|
||||
|
||||
#if HAL_EFI_DRONECAN_ENABLED
|
||||
#if AP_EFI_DRONECAN_ENABLED
|
||||
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
|
@ -165,5 +165,5 @@ void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating:
|
|||
copy_to_frontend();
|
||||
}
|
||||
|
||||
#endif // HAL_EFI_DRONECAN_ENABLED
|
||||
#endif // AP_EFI_DRONECAN_ENABLED
|
||||
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
#include "AP_EFI.h"
|
||||
#include "AP_EFI_Backend.h"
|
||||
|
||||
#if HAL_EFI_DRONECAN_ENABLED
|
||||
#if AP_EFI_DRONECAN_ENABLED
|
||||
#include <AP_UAVCAN/AP_UAVCAN.h>
|
||||
#include <uavcan/equipment/ice/reciprocating/Status.hpp>
|
||||
|
||||
|
@ -24,5 +24,5 @@ private:
|
|||
// singleton for trampoline
|
||||
static AP_EFI_DroneCAN *driver;
|
||||
};
|
||||
#endif // HAL_EFI_DRONECAN_ENABLED
|
||||
#endif // AP_EFI_DRONECAN_ENABLED
|
||||
|
||||
|
|
|
@ -13,6 +13,10 @@
|
|||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "AP_EFI_config.h"
|
||||
|
||||
#if AP_EFI_NWPWU_ENABLED
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
@ -22,8 +26,6 @@
|
|||
|
||||
#include "AP_EFI_NWPMU.h"
|
||||
|
||||
#if HAL_EFI_NWPWU_ENABLED
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_EFI_NWPMU::AP_EFI_NWPMU(AP_EFI &_frontend) :
|
||||
|
@ -131,4 +133,4 @@ void AP_EFI_NWPMU::update()
|
|||
copy_to_frontend();
|
||||
}
|
||||
|
||||
#endif // HAL_EFI_NWPWU_ENABLED
|
||||
#endif // AP_EFI_NWPWU_ENABLED
|
||||
|
|
|
@ -20,15 +20,12 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_EFI_config.h"
|
||||
|
||||
#if AP_EFI_NWPWU_ENABLED
|
||||
|
||||
#include "AP_EFI.h"
|
||||
#include "AP_EFI_Backend.h"
|
||||
#include <AP_CANManager/AP_CANSensor.h>
|
||||
|
||||
#ifndef HAL_EFI_NWPWU_ENABLED
|
||||
#define HAL_EFI_NWPWU_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS && BOARD_FLASH_SIZE > 1024
|
||||
#endif
|
||||
|
||||
#if HAL_EFI_NWPWU_ENABLED
|
||||
|
||||
class AP_EFI_NWPMU : public CANSensor, public AP_EFI_Backend {
|
||||
public:
|
||||
|
@ -111,5 +108,5 @@ private:
|
|||
};
|
||||
};
|
||||
|
||||
#endif // HAL_EFI_NWPWU_ENABLED
|
||||
#endif // AP_EFI_NWPWU_ENABLED
|
||||
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_CANManager/AP_CANSensor.h>
|
||||
|
||||
#ifndef HAL_EFI_ENABLED
|
||||
#define HAL_EFI_ENABLED !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024
|
||||
|
@ -10,8 +11,16 @@
|
|||
#define AP_EFI_BACKEND_DEFAULT_ENABLED HAL_EFI_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef HAL_EFI_DRONECAN_ENABLED
|
||||
#define HAL_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS && BOARD_FLASH_SIZE > 1024 && HAL_CANMANAGER_ENABLED
|
||||
#ifndef AP_EFI_CURRAWONG_ECU_ENABLED
|
||||
#define AP_EFI_CURRAWONG_ECU_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
#endif
|
||||
|
||||
#ifndef AP_EFI_DRONECAN_ENABLED
|
||||
#define AP_EFI_DRONECAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_EFI_NWPWU_ENABLED
|
||||
#define AP_EFI_NWPWU_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED && HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
#endif
|
||||
|
||||
#ifndef AP_EFI_SCRIPTING_ENABLED
|
||||
|
|
Loading…
Reference in New Issue