diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 016f827f31..5e4942f636 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -269,7 +269,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } // check adsb avoidance failsafe -#if ADSB_ENABLED == ENABLE +#if HAL_ADSB_ENABLED if (copter.failsafe.adsb) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected"); return false; @@ -687,7 +687,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) } // check adsb -#if ADSB_ENABLED == ENABLE +#if HAL_ADSB_ENABLED if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) { if (copter.failsafe.adsb) { check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected"); diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 981322c72f..f64042b9b8 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -166,7 +166,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(compass_cal_update, 100, 100), SCHED_TASK(accel_cal_update, 10, 100), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100), -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100), #endif #if ADVANCED_FAILSAFE == ENABLED @@ -513,7 +513,7 @@ void Copter::one_hz_loop() // log terrain data terrain_logging(); -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED adsb.set_is_flying(!ap.land_complete); #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index def684cc83..785f1c500d 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -65,6 +65,7 @@ #include #include #include +#include // Configuration #include "defines.h" @@ -112,7 +113,7 @@ # include # include #endif -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED # include #endif #if MODE_FOLLOW_ENABLED == ENABLED @@ -169,7 +170,7 @@ #include "UserParameters.h" #endif #include "Parameters.h" -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED #include "avoidance_adsb.h" #endif @@ -535,7 +536,7 @@ private: AC_InputManager_Heli input_manager; #endif -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED AP_ADSB adsb; // avoidance of adsb enabled vehicles (normally manned vehicles) @@ -667,7 +668,7 @@ private: void rotate_body_frame_to_NE(float &x, float &y); uint16_t get_pilot_speed_dn(); -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED // avoidance_adsb.cpp void avoidance_adsb_update(void); #endif @@ -948,7 +949,7 @@ private: #if MODE_SYSTEMID_ENABLED == ENABLED ModeSystemId mode_systemid; #endif -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED ModeAvoidADSB mode_avoid_adsb; #endif #if MODE_THROW_ENABLED == ENABLED diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 3938305374..fb526f26e2 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -279,7 +279,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) break; case MSG_ADSB_VEHICLE: { -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED CHECK_PAYLOAD_SIZE(ADSB_VEHICLE); copter.adsb.send_adsb_vehicle(chan); #endif @@ -501,7 +501,7 @@ void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command & void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) { -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) { // optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source copter.avoidance_adsb.handle_msg(msg); @@ -1301,7 +1301,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG: case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC: case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT: -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED copter.adsb.handle_message(chan, msg); #endif break; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 78efb96f92..f62b953106 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -679,7 +679,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(rpm_sensor, "RPM", AP_RPM), #endif -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED // @Group: ADSB_ // @Path: ../libraries/AP_ADSB/AP_ADSB.cpp GOBJECT(adsb, "ADSB_", AP_ADSB), diff --git a/ArduCopter/avoidance_adsb.cpp b/ArduCopter/avoidance_adsb.cpp index 1ecb5916f5..eb2227c5e5 100644 --- a/ArduCopter/avoidance_adsb.cpp +++ b/ArduCopter/avoidance_adsb.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #include -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED void Copter::avoidance_adsb_update(void) { adsb.update(); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 323db5dcb9..a6a6239e7f 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -252,12 +252,6 @@ # define PARACHUTE HAL_PARACHUTE_ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// ADSB support -#ifndef ADSB_ENABLED -# define ADSB_ENABLED !HAL_MINIMIZE_FEATURES -#endif - ////////////////////////////////////////////////////////////////////////////// // Nav-Guided - allows external nav computer to control vehicle #ifndef NAV_GUIDED @@ -731,7 +725,7 @@ #error SmartRTL requires ModeRTL which is disabled #endif -#if ADSB_ENABLED && !MODE_GUIDED_ENABLED +#if HAL_ADSB_ENABLED && !MODE_GUIDED_ENABLED #error ADSB requires ModeGuided which is disabled #endif diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 580521e1d3..6ee32eb323 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -121,7 +121,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode) break; #endif -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED case Mode::Number::AVOID_ADSB: ret = &mode_avoid_adsb; break; @@ -280,7 +280,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) logger.Write_Mode((uint8_t)control_mode, reason); gcs().send_message(MSG_HEARTBEAT); -#if ADSB_ENABLED == ENABLED +#if HAL_ADSB_ENABLED adsb.set_is_auto_mode((mode == Mode::Number::AUTO) || (mode == Mode::Number::RTL) || (mode == Mode::Number::GUIDED)); #endif