Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move is_valid_octal into AP_ADSB and rename to is_valid_callsign #12412

Merged
merged 2 commits into from Sep 30, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
19 changes: 18 additions & 1 deletion libraries/AP_ADSB/AP_ADSB.cpp
Expand Up @@ -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
*/
Expand Down Expand Up @@ -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;
}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ADSB/AP_ADSB.h
Expand Up @@ -85,6 +85,8 @@ class AP_ADSB {
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
Expand Down
43 changes: 43 additions & 0 deletions libraries/AP_ADSB/tests/test_adsb_callsign.cpp
@@ -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 changes: 7 additions & 0 deletions libraries/AP_ADSB/tests/wscript
@@ -0,0 +1,7 @@
#!/usr/bin/env python
# encoding: utf-8

def build(bld):
bld.ap_find_tests(
use='ap',
)
17 changes: 0 additions & 17 deletions libraries/AP_Math/AP_Math.cpp
Expand Up @@ -321,23 +321,6 @@ Vector3f rand_vec3f(void)
}
#endif

bool is_valid_octal(uint16_t octal)
{
// treat "octal" as decimal and test if any decimal digit is > 7
if (octal > 7777) {
return false;
} else if (octal % 10 > 7) {
return false;
} else if ((octal % 100)/10 > 7) {
return false;
} else if ((octal % 1000)/100 > 7) {
return false;
} else if ((octal % 10000)/1000 > 7) {
return false;
}
return true;
}

/*
return true if two rotations are equivalent
This copes with the fact that we have some duplicates, like ROLL_180_YAW_90 and PITCH_180_YAW_270
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_Math/AP_Math.h
Expand Up @@ -274,9 +274,6 @@ float rand_float(void);
// generate a random Vector3f of size 1
Vector3f rand_vec3f(void);

// confirm a value is a valid octal value
bool is_valid_octal(uint16_t octal) WARN_IF_UNUSED;

// return true if two rotations are equal
bool rotation_equal(enum Rotation r1, enum Rotation r2) WARN_IF_UNUSED;

Expand Down