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

include multiple encoding errors in OPEN_DRONE_ID_ARM_STATUS message #102

Merged
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 26 additions & 9 deletions RemoteIDModule/RemoteIDModule.ino
Original file line number Diff line number Diff line change
Expand Up @@ -131,39 +131,58 @@ void setup()
/*
check parsing of UAS_data, this checks ranges of values to ensure we
will produce a valid pack
returns nullptr on no error, or a string error
*/
static const char *check_parse(void)
{
String ret = "";

{
ODID_Location_encoded encoded {};
if (encodeLocationMessage(&encoded, &UAS_data.Location) != ODID_SUCCESS) {
return "bad LOCATION data";
ret += "LOC ";
}
}
{
ODID_System_encoded encoded {};
if (encodeSystemMessage(&encoded, &UAS_data.System) != ODID_SUCCESS) {
return "bad SYSTEM data";
ret += "SYS ";
}
}
{
ODID_BasicID_encoded encoded {};
if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
return "bad BASIC_ID data";
if (UAS_data.BasicIDValid[0] == 1) {
if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[0]) != ODID_SUCCESS) {
ret += "ID_1 ";
}
}
memset(&encoded, 0, sizeof(encoded));
if (UAS_data.BasicIDValid[1] == 1) {
if (encodeBasicIDMessage(&encoded, &UAS_data.BasicID[1]) != ODID_SUCCESS) {
ret += "ID_2 ";
}
}
}
{
ODID_SelfID_encoded encoded {};
if (encodeSelfIDMessage(&encoded, &UAS_data.SelfID) != ODID_SUCCESS) {
return "bad SELF_ID data";
ret += "SELF_ID ";
}
}
{
ODID_OperatorID_encoded encoded {};
if (encodeOperatorIDMessage(&encoded, &UAS_data.OperatorID) != ODID_SUCCESS) {
return "bad OPERATOR_ID data";
ret += "OP_ID ";
}
}
if (ret.length() > 0) {
// if all errors would occur in this function, it will fit in
// 50 chars that is also the max for the arm status message
static char return_string[50];
memset(return_string, 0, sizeof(return_string));
snprintf(return_string, sizeof(return_string-1), "bad %s data", ret.c_str());
return return_string;
}
return nullptr;
}

Expand Down Expand Up @@ -306,9 +325,7 @@ static void set_data(Transport &t)
}

const char *reason = check_parse();
if (reason == nullptr) {
t.arm_status_check(reason);
}
t.arm_status_check(reason);
t.set_parse_fail(reason);

arm_check_ok = (reason==nullptr);
Expand Down
54 changes: 39 additions & 15 deletions RemoteIDModule/transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,24 +45,49 @@ uint8_t Transport::arm_status_check(const char *&reason)
return status;
}

String ret = "";

if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
reason = "missing location message";
} else if (!g.have_basic_id_info() && (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms)) {
reason = "missing basic_id message";
} else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
reason = "missing self_id message";
} else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
reason = "missing operator_id message";
} else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
ret += "LOC ";
}
if (!g.have_basic_id_info()) {
// if there is no basic ID data stored in the parameters give warning. If basic ID data are streamed to RID device,
// it will store them in the parameters
ret += "ID ";
}

if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
ret += "SELF_ID ";
}

if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
ret += "OP_ID ";
}

if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
// we use location age limit for system as the operator location needs to come in as fast
// as the vehicle location for FAA standard
reason = "missing system message";
} else if (location.latitude == 0 && location.longitude == 0) {
reason = "Bad location";
} else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
reason = "Bad operator location";
} else if (reason == nullptr) {
ret += "SYS ";
}

if (location.latitude == 0 && location.longitude == 0) {
ret += "LOC ";
}

if (system.operator_latitude == 0 && system.operator_longitude == 0) {
ret += "OP_LOC ";
}

if (ret.length() == 0 && reason == nullptr) {
status = MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
} else {
static char return_string[200];
memset(return_string, 0, sizeof(return_string));
if (reason != nullptr) {
strlcpy(return_string, reason, sizeof(return_string));
}
strlcat(return_string, ret.c_str(), sizeof(return_string));
reason = return_string;
}

return status;
Expand Down Expand Up @@ -128,4 +153,3 @@ bool Transport::check_signature(uint8_t sig_length, uint8_t data_len, uint32_t s
}
return false;
}

Loading