Sub: Remove ADSB support
This commit is contained in:
parent
5d78cacd58
commit
105eae0e86
@ -36,7 +36,6 @@
|
|||||||
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
//#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands
|
||||||
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
//#define OPTFLOW DISABLED // disable optical flow sensor to save 5K of flash space
|
||||||
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
|
//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry
|
||||||
#define ADSB_ENABLED DISABLED // disable ADSB support
|
|
||||||
|
|
||||||
// features below are disabled by default on all boards
|
// features below are disabled by default on all boards
|
||||||
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
|
||||||
|
@ -137,9 +137,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(rpm_update, 10, 200),
|
SCHED_TASK(rpm_update, 10, 200),
|
||||||
SCHED_TASK(compass_cal_update, 100, 100),
|
SCHED_TASK(compass_cal_update, 100, 100),
|
||||||
SCHED_TASK(accel_cal_update, 10, 100),
|
SCHED_TASK(accel_cal_update, 10, 100),
|
||||||
#if ADSB_ENABLED == ENABLED
|
|
||||||
SCHED_TASK(adsb_update, 1, 100),
|
|
||||||
#endif
|
|
||||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||||
SCHED_TASK(frsky_telemetry_send, 5, 75),
|
SCHED_TASK(frsky_telemetry_send, 5, 75),
|
||||||
#endif
|
#endif
|
||||||
|
@ -1987,9 +1987,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_ADSB_VEHICLE:
|
case MAVLINK_MSG_ID_ADSB_VEHICLE:
|
||||||
#if ADSB_ENABLED == ENABLED
|
|
||||||
sub.adsb.update_vehicle(msg);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
} // end switch
|
} // end switch
|
||||||
|
@ -1098,7 +1098,7 @@ const AP_Param::Info Sub::var_info[] = {
|
|||||||
|
|
||||||
// @Group: ADSB_
|
// @Group: ADSB_
|
||||||
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
|
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
|
||||||
GOBJECT(adsb, "ADSB_", AP_ADSB),
|
// GOBJECT(adsb, "ADSB_", AP_ADSB),
|
||||||
|
|
||||||
// @Param: AUTOTUNE_AXES
|
// @Param: AUTOTUNE_AXES
|
||||||
// @DisplayName: Autotune axis bitmask
|
// @DisplayName: Autotune axis bitmask
|
||||||
|
@ -90,7 +90,6 @@
|
|||||||
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
|
||||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_ADSB/AP_ADSB.h>
|
|
||||||
#include <AP_RPM/AP_RPM.h>
|
#include <AP_RPM/AP_RPM.h>
|
||||||
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
#include <AC_InputManager/AC_InputManager.h> // Pilot input handling library
|
||||||
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
|
#include <AC_InputManager/AC_InputManager_Heli.h> // Heli specific pilot input handling library
|
||||||
@ -518,8 +517,6 @@ private:
|
|||||||
AC_InputManager_Heli input_manager;
|
AC_InputManager_Heli input_manager;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_ADSB adsb {ahrs};
|
|
||||||
|
|
||||||
// use this to prevent recursion during sensor init
|
// use this to prevent recursion during sensor init
|
||||||
bool in_mavlink_delay;
|
bool in_mavlink_delay;
|
||||||
|
|
||||||
@ -746,8 +743,6 @@ private:
|
|||||||
void autotune_updating_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float target, float measurement_max);
|
void autotune_updating_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float target, float measurement_max);
|
||||||
void autotune_updating_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float target, float measurement_min, float measurement_max);
|
void autotune_updating_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float target, float measurement_min, float measurement_max);
|
||||||
void autotune_twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
|
void autotune_twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
|
||||||
void adsb_update(void);
|
|
||||||
void adsb_handle_vehicle_threats(void);
|
|
||||||
bool brake_init(bool ignore_checks);
|
bool brake_init(bool ignore_checks);
|
||||||
void brake_run();
|
void brake_run();
|
||||||
bool circle_init(bool ignore_checks);
|
bool circle_init(bool ignore_checks);
|
||||||
|
@ -1,62 +0,0 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
/*
|
|
||||||
* adsb.cpp
|
|
||||||
* Copyright (C) Tom Pittenger 2015
|
|
||||||
*
|
|
||||||
* This file is free software: you can redistribute it and/or modify it
|
|
||||||
* under the terms of the GNU General Public License as published by the
|
|
||||||
* Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* This file is distributed in the hope that it will be useful, but
|
|
||||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
||||||
* See the GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License along
|
|
||||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "Sub.h"
|
|
||||||
|
|
||||||
#if ADSB_ENABLED == ENABLED
|
|
||||||
|
|
||||||
/*
|
|
||||||
* this module deals with ADS-B handling for ArduPilot
|
|
||||||
* ADS-B is an RF based collision avoidance protocol to tell nearby aircraft your location
|
|
||||||
* https://en.wikipedia.org/wiki/Automatic_dependent_surveillance_%E2%80%93_broadcast
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
handle periodic adsb database maintenance and handle threats
|
|
||||||
*/
|
|
||||||
void Sub::adsb_update(void)
|
|
||||||
{
|
|
||||||
adsb.update();
|
|
||||||
adsb_handle_vehicle_threats();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Handle ADS-B based threats which are platform dependent
|
|
||||||
*/
|
|
||||||
void Sub::adsb_handle_vehicle_threats(void)
|
|
||||||
{
|
|
||||||
// handle clearing of threat
|
|
||||||
if (adsb.get_is_evading_threat() && !adsb.get_another_vehicle_within_radius()) {
|
|
||||||
adsb.set_is_evading_threat(false);
|
|
||||||
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_ADSB, ERROR_CODE_FAILSAFE_RESOLVED);
|
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "ADS-B threat cleared");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// handle new threat
|
|
||||||
if (!adsb.get_is_evading_threat() && adsb.get_another_vehicle_within_radius()) {
|
|
||||||
adsb.set_is_evading_threat(true);
|
|
||||||
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_ADSB, ERROR_CODE_FAILSAFE_OCCURRED);
|
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL, "ADS-B threat!");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // #ADSB_ENABLED
|
|
@ -326,12 +326,6 @@
|
|||||||
# define PARACHUTE ENABLED
|
# define PARACHUTE ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// ADSB support
|
|
||||||
#ifndef ADSB_ENABLED
|
|
||||||
# define ADSB_ENABLED ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Nav-Guided - allows external nav computer to control vehicle
|
// Nav-Guided - allows external nav computer to control vehicle
|
||||||
#ifndef NAV_GUIDED
|
#ifndef NAV_GUIDED
|
||||||
|
@ -58,4 +58,3 @@ LIBRARIES += AP_RPM
|
|||||||
LIBRARIES += AC_PrecLand
|
LIBRARIES += AC_PrecLand
|
||||||
LIBRARIES += AP_IRLock
|
LIBRARIES += AP_IRLock
|
||||||
LIBRARIES += AC_InputManager
|
LIBRARIES += AC_InputManager
|
||||||
LIBRARIES += AP_ADSB
|
|
||||||
|
@ -7,7 +7,6 @@ def build(bld):
|
|||||||
name=vehicle + '_libs',
|
name=vehicle + '_libs',
|
||||||
vehicle=vehicle,
|
vehicle=vehicle,
|
||||||
libraries=bld.ap_common_vehicle_libraries() + [
|
libraries=bld.ap_common_vehicle_libraries() + [
|
||||||
'AP_ADSB',
|
|
||||||
'AC_AttitudeControl',
|
'AC_AttitudeControl',
|
||||||
'AC_Fence',
|
'AC_Fence',
|
||||||
'AC_PID',
|
'AC_PID',
|
||||||
|
Loading…
Reference in New Issue
Block a user