Browse Source

AP_ADSB: use AP::ahrs() singleton

master
Peter Barker 7 years ago committed by Francisco Ferreira
parent
commit
ae3099ef4b
  1. 4
      libraries/AP_ADSB/AP_ADSB.cpp
  2. 7
      libraries/AP_ADSB/AP_ADSB.h

4
libraries/AP_ADSB/AP_ADSB.cpp

@ -161,7 +161,7 @@ void AP_ADSB::deinit(void) @@ -161,7 +161,7 @@ void AP_ADSB::deinit(void)
void AP_ADSB::update(void)
{
// update _my_loc
if (!_ahrs.get_position(_my_loc)) {
if (!AP::ahrs().get_position(_my_loc)) {
_my_loc.zero();
}
@ -506,7 +506,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan) @@ -506,7 +506,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
const uint64_t gps_time = gps.time_epoch_usec();
const uint32_t utcTime = gps_time / 1000000ULL;
const AP_Baro &baro = _ahrs.get_baro();
const AP_Baro &baro = AP::ahrs().get_baro();
int32_t altPres = INT_MAX;
if (baro.healthy()) {
// Altitude difference between 101325 (Pascals) and current pressure. Result in millimeters

7
libraries/AP_ADSB/AP_ADSB.h

@ -31,8 +31,7 @@ @@ -31,8 +31,7 @@
class AP_ADSB {
public:
AP_ADSB(const AP_AHRS &ahrs)
: _ahrs(ahrs)
AP_ADSB()
{
AP_Param::setup_object_defaults(this, var_info);
}
@ -109,10 +108,6 @@ private: @@ -109,10 +108,6 @@ private:
// handle ADS-B transceiver report for ping2020
void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t* msg);
// reference to AHRS, so we can ask for our position,
// heading and speed
const AP_AHRS &_ahrs;
AP_Int8 _enabled;
Location_Class _my_loc;

Loading…
Cancel
Save