mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: rename ADSB_ENABLED to HAL_ADSB_ENABLED and remove from config
This commit is contained in:
parent
fc67c2c13b
commit
b8f613c965
@ -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");
|
||||
|
@ -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
|
||||
|
||||
|
@ -65,6 +65,7 @@
|
||||
#include <AC_AutoTune/AC_AutoTune.h>
|
||||
#include <AP_Parachute/AP_Parachute.h>
|
||||
#include <AC_Sprayer/AC_Sprayer.h>
|
||||
#include <AP_ADSB/AP_ADSB.h>
|
||||
|
||||
// Configuration
|
||||
#include "defines.h"
|
||||
@ -112,7 +113,7 @@
|
||||
# include <AC_PrecLand/AC_PrecLand.h>
|
||||
# include <AP_IRLock/AP_IRLock.h>
|
||||
#endif
|
||||
#if ADSB_ENABLED == ENABLED
|
||||
#if HAL_ADSB_ENABLED
|
||||
# include <AP_ADSB/AP_ADSB.h>
|
||||
#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
|
||||
|
@ -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;
|
||||
|
@ -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),
|
||||
|
@ -1,7 +1,7 @@
|
||||
#include "Copter.h"
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
|
||||
#if ADSB_ENABLED == ENABLED
|
||||
#if HAL_ADSB_ENABLED
|
||||
void Copter::avoidance_adsb_update(void)
|
||||
{
|
||||
adsb.update();
|
||||
|
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user