Copter: Add support for ADS-B

This commit is contained in:
Tom Pittenger 2015-11-25 15:22:21 -08:00 committed by Randy Mackay
parent 084b607862
commit 34d6d985e9
7 changed files with 63 additions and 1 deletions

View File

@ -140,6 +140,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(read_receiver_rssi, 40, 75),
SCHED_TASK(rpm_update, 40, 200),
SCHED_TASK(compass_cal_update, 4, 100),
SCHED_TASK(adsb_update, 400, 100),
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 80, 75),
#endif

View File

@ -100,6 +100,7 @@
#endif
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
#include <AP_Terrain/AP_Terrain.h>
#include <AP_ADSB/AP_ADSB.h>
#include <AP_RPM/AP_RPM.h>
#if PRECISION_LANDING == ENABLED
#include <AC_PrecLand/AC_PrecLand.h>
@ -516,6 +517,8 @@ private:
AC_InputManager_Heli input_manager;
#endif
AP_ADSB adsb {ahrs};
// use this to prevent recursion during sensor init
bool in_mavlink_delay;
@ -731,6 +734,8 @@ 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_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 adsb_update(void);
void adsb_handle_vehicle_threats(void);
bool brake_init(bool ignore_checks);
void brake_run();
bool circle_init(bool ignore_checks);

View File

@ -1933,6 +1933,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_ADSB_VEHICLE:
copter.adsb.update_vehicle(msg);
break;
} // end switch
} // end handle mavlink

View File

@ -1087,6 +1087,10 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
GOBJECT(rpm_sensor, "RPM", AP_RPM),
// @Group: ADSB_
// @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
GOBJECT(adsb, "ADSB_", AP_ADSB),
// @Param: AUTOTUNE_AXES
// @DisplayName: Autotune axis bitmask
// @Description: 1-byte bitmap of axes to autotune

View File

@ -145,6 +145,9 @@ public:
k_param_gps_glitch, // deprecated
k_param_baro_glitch, // 71 - deprecated
// AP_ADSB Library
k_param_adsb, // 72
// 74: precision landing object
k_param_precland = 74,

44
ArduCopter/adsb.cpp Normal file
View File

@ -0,0 +1,44 @@
/// -*- 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 "Copter.h"
/*
* 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 Copter::adsb_update(void)
{
adsb.update();
adsb_handle_vehicle_threats();
}
/*
* Handle ADS-B based threats which are platform dependent
*/
void Copter::adsb_handle_vehicle_threats(void)
{
}

View File

@ -60,3 +60,4 @@ LIBRARIES += AP_RPM
LIBRARIES += AC_PrecLand
LIBRARIES += AP_IRLock
LIBRARIES += AC_InputManager
LIBRARIES += AP_ADSB