|
|
|
@ -260,7 +260,6 @@ void AP_ADSB::detect_instance(uint8_t instance)
@@ -260,7 +260,6 @@ void AP_ADSB::detect_instance(uint8_t instance)
|
|
|
|
|
#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED |
|
|
|
|
if (AP_ADSB_uAvionix_MAVLink::detect()) { |
|
|
|
|
_backend[instance] = new AP_ADSB_uAvionix_MAVLink(*this, instance); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
@ -269,7 +268,6 @@ void AP_ADSB::detect_instance(uint8_t instance)
@@ -269,7 +268,6 @@ void AP_ADSB::detect_instance(uint8_t instance)
|
|
|
|
|
#if HAL_ADSB_UCP_ENABLED |
|
|
|
|
if (AP_ADSB_uAvionix_UCP::detect()) { |
|
|
|
|
_backend[instance] = new AP_ADSB_uAvionix_UCP(*this, instance); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
@ -283,6 +281,7 @@ void AP_ADSB::detect_instance(uint8_t instance)
@@ -283,6 +281,7 @@ void AP_ADSB::detect_instance(uint8_t instance)
|
|
|
|
|
#endif |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// get instance type from instance
|
|
|
|
@ -367,10 +366,9 @@ void AP_ADSB::update(void)
@@ -367,10 +366,9 @@ void AP_ADSB::update(void)
|
|
|
|
|
|
|
|
|
|
#ifndef ADSB_STATIC_CALLSIGN |
|
|
|
|
if (!out_state.cfg.was_set_externally) { |
|
|
|
|
set_callsign("PING", true); |
|
|
|
|
set_callsign("ARDU", true); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign); |
|
|
|
|
out_state.last_config_ms = 0; // send now
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -848,6 +846,29 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const
@@ -848,6 +846,29 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const
|
|
|
|
|
AP::logger().WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* @brief Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value stored on a GCS as a string field in different format, but then transmitted over mavlink as a float which is always a decimal. |
|
|
|
|
* baseIn: base of input number |
|
|
|
|
* inputNumber: value currently in base "baseIn" to be converted to base "baseOut" |
|
|
|
|
* |
|
|
|
|
* Example: convert ADSB squawk octal "1200" stored in memory as 0x0280 to 0x04B0 |
|
|
|
|
* uint16_t squawk_decimal = convertMathBase(8, squawk_octal); |
|
|
|
|
*/ |
|
|
|
|
uint32_t AP_ADSB::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber) |
|
|
|
|
{ |
|
|
|
|
// Our only sensible input bases are 16 and 8
|
|
|
|
|
if (baseIn != 8 && baseIn != 16) { |
|
|
|
|
return inputNumber; |
|
|
|
|
} |
|
|
|
|
uint32_t outputNumber = 0; |
|
|
|
|
for (uint8_t i=0; i < 10; i++) { |
|
|
|
|
outputNumber += (inputNumber % 10) * powf(baseIn, i); |
|
|
|
|
inputNumber /= 10; |
|
|
|
|
if (inputNumber == 0) break; |
|
|
|
|
} |
|
|
|
|
return outputNumber; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
AP_ADSB *AP::ADSB() |
|
|
|
|
{ |
|
|
|
|
return AP_ADSB::get_singleton(); |
|
|
|
|