Browse Source

AP_ADSB: move is_valid_octal to is_valid_callsign and add tests for it

master
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
13352a4ca7
  1. 19
      libraries/AP_ADSB/AP_ADSB.cpp
  2. 2
      libraries/AP_ADSB/AP_ADSB.h
  3. 43
      libraries/AP_ADSB/tests/test_adsb_callsign.cpp
  4. 7
      libraries/AP_ADSB/tests/wscript

19
libraries/AP_ADSB/AP_ADSB.cpp

@ -200,6 +200,23 @@ void AP_ADSB::deinit(void) @@ -200,6 +200,23 @@ void AP_ADSB::deinit(void)
}
}
bool AP_ADSB::is_valid_callsign(uint16_t octal)
{
// treat "octal" as decimal and test if any decimal digit is > 7
if (octal > 7777) {
return false;
}
while (octal != 0) {
if (octal % 10 > 7) {
return false;
}
octal /= 10;
}
return true;
}
/*
* periodic update to handle vehicle timeouts and trigger collision detection
*/
@ -252,7 +269,7 @@ void AP_ADSB::update(void) @@ -252,7 +269,7 @@ void AP_ADSB::update(void)
if (out_state.cfg.squawk_octal_param != out_state.cfg.squawk_octal) {
// param changed, check that it's a valid octal
if (!is_valid_octal(out_state.cfg.squawk_octal_param)) {
if (!is_valid_callsign(out_state.cfg.squawk_octal_param)) {
// invalid, reset it to default
out_state.cfg.squawk_octal_param = ADSB_SQUAWK_OCTAL_DEFAULT;
}

2
libraries/AP_ADSB/AP_ADSB.h

@ -85,6 +85,8 @@ public: @@ -85,6 +85,8 @@ public:
void set_special_ICAO_target(const uint32_t new_icao_target) { _special_ICAO_target = (int32_t)new_icao_target; };
bool is_special_vehicle(uint32_t icao) const { return _special_ICAO_target != 0 && (_special_ICAO_target == (int32_t)icao); }
// confirm a value is a valid callsign
static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED;
private:
// initialize _vehicle_list

43
libraries/AP_ADSB/tests/test_adsb_callsign.cpp

@ -0,0 +1,43 @@ @@ -0,0 +1,43 @@
#include <AP_gtest.h>
#include <AP_ADSB/AP_ADSB.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
TEST(IsValidCallsign, Valid)
{
EXPECT_TRUE(AP_ADSB::is_valid_callsign(7777));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(777));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(77));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(7));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(0));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(1111));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(111));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(11));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(1));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(0));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(7654));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(321));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(23));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(5));
EXPECT_TRUE(AP_ADSB::is_valid_callsign(5));
}
TEST(IsValidCallsign, Invalid)
{
EXPECT_FALSE(AP_ADSB::is_valid_callsign(17777));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(8888));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(888));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(88));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(8));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(9));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(7778));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(7788));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(7888));
EXPECT_FALSE(AP_ADSB::is_valid_callsign(8888));
}
AP_GTEST_MAIN()
#pragma GCC diagnostic pop

7
libraries/AP_ADSB/tests/wscript

@ -0,0 +1,7 @@ @@ -0,0 +1,7 @@
#!/usr/bin/env python
# encoding: utf-8
def build(bld):
bld.ap_find_tests(
use='ap',
)
Loading…
Cancel
Save