AP_ADSB: Driver cleanup and refactor

This commit is contained in:
Tom Pittenger 2022-06-01 11:33:52 -07:00 committed by Tom Pittenger
parent 07be987073
commit 0645aee865
4 changed files with 32 additions and 34 deletions

View File

@ -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)
#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)
#endif
break;
}
}
// get instance type from instance
@ -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
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();

View File

@ -151,6 +151,11 @@ public:
// confirm a value is a valid callsign
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;
// 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.
static uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber);
// Trigger a Mode 3/A transponder IDENT. This should only be done when requested to do so by an Air Traffic Controller.
// See wikipedia for IDENT explaination https://en.wikipedia.org/wiki/Transponder_(aeronautics)
bool ident_start() {

View File

@ -397,7 +397,7 @@ void AP_ADSB_Sagetech::send_msg_Installation()
// // convert a decimal 123456 to 0x123456
// TODO: do a proper conversion. The param contains "131313" but what gets transmitted over the air is 0x200F1.
const uint32_t icao_hex = convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param);
const uint32_t icao_hex = AP_ADSB::convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param);
put_le24_ptr(&pkt.payload[0], icao_hex);
memcpy(&pkt.payload[3], &_frontend.out_state.cfg.callsign, 8);
@ -452,7 +452,7 @@ void AP_ADSB_Sagetech::send_msg_Operating()
// squawk
// param is saved as native octal so we need convert back to
// decimal because Sagetech will convert it back to octal
uint16_t squawk = convert_base_to_decimal(8, last_operating_squawk);
const uint16_t squawk = AP_ADSB::convert_base_to_decimal(8, last_operating_squawk);
put_le16_ptr(&pkt.payload[0], squawk);
// altitude
@ -526,28 +526,5 @@ void AP_ADSB_Sagetech::send_msg_GPS()
send_msg(pkt);
}
/*
* 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_Sagetech::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; inputNumber != 0; i++) {
outputNumber += (inputNumber % 10) * powf(10, i);
inputNumber /= 10;
}
return outputNumber;
}
#endif // HAL_ADSB_SAGETECH_ENABLED

View File

@ -137,11 +137,6 @@ private:
// send msg to request a packet by type
void request_packet(const MsgType_XP type);
// 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.
uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber);
// timers for each out-bound packet
uint32_t last_packet_initialize_ms;
uint32_t last_packet_PreFlight_ms;