SRV_Channel: convert APM_BUILD_COPTER_OR_HELI() to APM_BUILD_COPTER_OR_HELI

This commit is contained in:
Andy Piper 2021-10-25 18:07:58 +01:00 committed by Andrew Tridgell
parent 50b90c2d2a
commit 9bea417d5c

View File

@ -27,7 +27,7 @@
#include <AP_UAVCAN/AP_UAVCAN.h>
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#include <AP_KDECAN/AP_KDECAN.h>
#endif
#include <AP_ToshibaCAN/AP_ToshibaCAN.h>
@ -399,7 +399,7 @@ void SRV_Channels::push()
}
case AP_CANManager::Driver_Type_KDECAN: {
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_COPTER_OR_HELI() || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
if (ap_kdecan == nullptr) {
continue;