Skip to content

Commit 4d71ebf

Browse files
BluemarkInnovationstridge
authored andcommitted
added region parameter
1 parent 4dea4e6 commit 4d71ebf

File tree

4 files changed

+156
-9
lines changed

4 files changed

+156
-9
lines changed

RemoteIDModule/RemoteIDModule.ino

Lines changed: 98 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -128,6 +128,33 @@ void setup()
128128
#define IMIN(x,y) ((x)<(y)?(x):(y))
129129
#define ODID_COPY_STR(to, from) strncpy(to, (const char*)from, IMIN(sizeof(to), sizeof(from)))
130130

131+
/*
132+
check if a UASID is valid as a serial number
133+
*/
134+
static bool valid_UASID_serialnum(const char *uasid)
135+
{
136+
const auto uasid_len = strnlen(uasid, sizeof(UAS_data.BasicID[0].UASID));
137+
// 5th char is length field
138+
if (uasid_len < 5 || !isxdigit(uasid[4]) != 0) {
139+
return false;
140+
}
141+
char str[2] {};
142+
str[0] = uasid[4];
143+
const uint8_t sn_length = strtol(str, NULL, 16) + 5;
144+
if (sn_length != uasid_len && sn_length > 5) {
145+
return false;
146+
}
147+
//check also for invalid chars
148+
for (unsigned i = 0; i < uasid_len; i++) {
149+
const auto c = uasid[i];
150+
if (islower(c) || c == 'I' || c == 'O') {
151+
// only capital letters and digits are allowed. Char I and O are not allowed.
152+
return false;
153+
}
154+
}
155+
return true;
156+
}
157+
131158
/*
132159
check parsing of UAS_data, this checks ranges of values to ensure we
133160
will produce a valid pack
@@ -136,6 +163,7 @@ void setup()
136163
static const char *check_parse(void)
137164
{
138165
String ret = "";
166+
const uint32_t required = g.get_required_features();
139167

140168
{
141169
ODID_Location_encoded encoded {};
@@ -175,14 +203,83 @@ static const char *check_parse(void)
175203
ret += "OP_ID ";
176204
}
177205
}
206+
207+
bool serial_number_configured = false;
208+
bool session_ID_configured = false;
209+
bool CAA_registration_ID_configured = false; //only mandatory in Japan
210+
211+
// BasicID checks
212+
if (UAS_data.BasicIDValid[0] == 1) {
213+
if (UAS_data.BasicID[0].IDType == ODID_IDTYPE_SERIAL_NUMBER) {
214+
serial_number_configured = true;
215+
} else if (UAS_data.BasicID[0].IDType == ODID_IDTYPE_CAA_REGISTRATION_ID) {
216+
CAA_registration_ID_configured = true;
217+
} else if (UAS_data.BasicID[0].IDType == ODID_IDTYPE_SPECIFIC_SESSION_ID) {
218+
session_ID_configured = true;
219+
}
220+
}
221+
222+
if (UAS_data.BasicIDValid[1] == 1) {
223+
if (UAS_data.BasicID[1].IDType == ODID_IDTYPE_SERIAL_NUMBER) {
224+
if (!serial_number_configured) { //only one serial number is allowed
225+
serial_number_configured = true;
226+
} else {
227+
ret += "DBL_SER_NUM ";
228+
}
229+
} else if (UAS_data.BasicID[1].IDType == ODID_IDTYPE_CAA_REGISTRATION_ID) {
230+
if (!CAA_registration_ID_configured) { //only one CAA registration ID is allowed
231+
CAA_registration_ID_configured = true;
232+
} else {
233+
ret += "DBL_CAA_ID ";
234+
}
235+
} else if (UAS_data.BasicID[1].IDType== ODID_IDTYPE_SPECIFIC_SESSION_ID) {
236+
if (!session_ID_configured) { //only one session ID is allowed
237+
session_ID_configured = true;
238+
} else {
239+
ret += "DBL_SESS_ID ";
240+
}
241+
}
242+
}
243+
244+
if (!serial_number_configured && (required & REG_REQUIRE_SERIAL_NUM)) {
245+
ret += "SER_NUM ";
246+
}
247+
248+
if (!serial_number_configured && !session_ID_configured && (required & REG_REQUIRE_SERIAL_OR_SESSION)) {
249+
ret += "SER_SESS ";
250+
}
251+
252+
if (!CAA_registration_ID_configured && (required & REG_REQUIRE_REG_ID)) {
253+
ret += "REG_ID ";
254+
}
255+
256+
if (strlen(UAS_data.OperatorID.OperatorId) <= 0 && (required & REG_REQUIRE_OPERATOR_ID)) {
257+
// basic check if the operator field has data. For the EU legislation an additional check could be implemented.
258+
ret += "OP_ID ";
259+
}
260+
261+
if (UAS_data.BasicIDValid[0] == 1 &&
262+
serial_number_configured &&
263+
UAS_data.BasicID[0].IDType == ODID_IDTYPE_SERIAL_NUMBER &&
264+
!valid_UASID_serialnum(UAS_data.BasicID[0].UASID)) {
265+
ret += "SER_NUM_VAL ";
266+
}
267+
268+
if (UAS_data.BasicIDValid[1] == 1 &&
269+
UAS_data.BasicID[1].IDType == ODID_IDTYPE_SERIAL_NUMBER &&
270+
!valid_UASID_serialnum(UAS_data.BasicID[1].UASID)) {
271+
ret += "SER_NUM_VAL ";
272+
}
273+
178274
if (ret.length() > 0) {
179275
// if all errors would occur in this function, it will fit in
180276
// 50 chars that is also the max for the arm status message
181277
static char return_string[50];
182278
memset(return_string, 0, sizeof(return_string));
183-
snprintf(return_string, sizeof(return_string-1), "bad %s data", ret.c_str());
279+
snprintf(return_string, sizeof(return_string)-1, "bad %s data", ret.c_str());
184280
return return_string;
185281
}
282+
186283
return nullptr;
187284
}
188285

RemoteIDModule/parameters.cpp

Lines changed: 24 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,8 @@ const Parameters::Param Parameters::params[] = {
3838
{ "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
3939
{ "MAVLINK_SYSID", Parameters::ParamType::UINT8, (const void*)&g.mavlink_sysid, 0, 0, 254 },
4040
{ "OPTIONS", Parameters::ParamType::UINT8, (const void*)&g.options, 0, 0, 254 },
41-
{ "TO_DEFAULTS", Parameters::ParamType::UINT8, (const void*)&g.to_factory_defaults, 0, 0, 1 }, //if set to 1, reset to factory defaults and make 0.
41+
{ "TO_DEFAULTS", Parameters::ParamType::UINT8, (const void*)&g.to_factory_defaults, 0, 0, 1 }, //if set to 1, reset to factory defaults and make 0.
42+
{ "REGION", Parameters::ParamType::UINT8, (const void*)&g.region, 0, 0, 3 }, // 0 = world, 1 = USA, 2 = Japan, 3 = EU
4243
{ "DONE_INIT", Parameters::ParamType::UINT8, (const void*)&g.done_init, 0, 0, 0, PARAM_FLAG_HIDDEN},
4344
{ "", Parameters::ParamType::NONE, nullptr, },
4445
};
@@ -496,3 +497,25 @@ bool Parameters::remove_public_key(uint8_t i)
496497
name[strlen(name)-2] = '1'+i;
497498
return set_by_name_char64(name, "");
498499
}
500+
501+
/*
502+
get required features based on region
503+
There are 4 regions: 0 = world, 1 = USA, 2 = Japan, 3 = EU
504+
for now region world is treated the same as the USA
505+
checks are based on this table: https://github.com/opendroneid/opendroneid-core-c#comparison
506+
and requirements on the serial number (ANSI/CTA-2063-A)
507+
*/
508+
uint32_t Parameters::get_required_features(void) const
509+
{
510+
switch (region) {
511+
case Region::EU:
512+
return REG_REQUIRE_LOC | REG_REQUIRE_BASIC_ID | REG_REQUIRE_OPERATOR_ID | REG_REQUIRE_OPERATOR_LOC | REG_REQUIRE_OPERATOR_ID | REG_REQUIRE_SERIAL_NUM;
513+
case Region::JAPAN:
514+
return REG_REQUIRE_LOC | REG_REQUIRE_BASIC_ID | REG_REQUIRE_OPERATOR_ID | REG_REQUIRE_OPERATOR_LOC | REG_REQUIRE_SERIAL_NUM;
515+
case Region::WORLD:
516+
case Region::USA:
517+
default:
518+
return REG_REQUIRE_LOC | REG_REQUIRE_BASIC_ID | REG_REQUIRE_OPERATOR_ID | REG_REQUIRE_SYSTEM | REG_REQUIRE_OPERATOR_LOC | REG_REQUIRE_SERIAL_OR_SESSION;
519+
}
520+
}
521+

RemoteIDModule/parameters.h

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,26 @@
1010
#define PARAM_FLAG_PASSWORD (1U<<0)
1111
#define PARAM_FLAG_HIDDEN (1U<<1)
1212

13+
enum class Region : uint8_t {
14+
WORLD=0,
15+
USA=1,
16+
JAPAN=2,
17+
EU=3,
18+
};
19+
20+
/*
21+
bits for which fields are required. Based on the region
22+
*/
23+
#define REG_REQUIRE_LOC (1U<<0)
24+
#define REG_REQUIRE_BASIC_ID (1U<<1)
25+
#define REG_REQUIRE_SELF_ID (1U<<2)
26+
#define REG_REQUIRE_OPERATOR_ID (1U<<3)
27+
#define REG_REQUIRE_SYSTEM (1U<<4)
28+
#define REG_REQUIRE_OPERATOR_LOC (1U<<5)
29+
#define REG_REQUIRE_SERIAL_NUM (1U<<6)
30+
#define REG_REQUIRE_SERIAL_OR_SESSION (1U<<7)
31+
#define REG_REQUIRE_REG_ID (1U<<8)
32+
1333
class Parameters {
1434
public:
1535
int8_t lock_level;
@@ -37,6 +57,8 @@ class Parameters {
3757
uint8_t wifi_channel = 6;
3858
uint8_t to_factory_defaults = 0;
3959
uint8_t options;
60+
Region region;
61+
4062
struct {
4163
char b64_key[64];
4264
} public_keys[MAX_PUBLIC_KEYS];
@@ -102,6 +124,9 @@ class Parameters {
102124
static uint16_t param_count_float(void);
103125
static int16_t param_index_float(const Param *p);
104126

127+
// get the REG_REQUIRE features for the region
128+
uint32_t get_required_features(void) const;
129+
105130
private:
106131
void load_defaults(void);
107132
};

RemoteIDModule/transport.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
#include "parameters.h"
77
#include "util.h"
88
#include "monocypher.h"
9+
#include <opendroneid.h>
910

1011
const char *Transport::parse_fail = "uninitialised";
1112

@@ -36,6 +37,7 @@ uint8_t Transport::arm_status_check(const char *&reason)
3637
const uint32_t max_age_location_ms = 3000;
3738
const uint32_t max_age_other_ms = 22000;
3839
const uint32_t now_ms = millis();
40+
const uint32_t required = g.get_required_features();
3941

4042
uint8_t status = MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
4143

@@ -47,34 +49,34 @@ uint8_t Transport::arm_status_check(const char *&reason)
4749

4850
String ret = "";
4951

50-
if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
52+
if ((required & REG_REQUIRE_LOC) && (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms)) {
5153
ret += "LOC ";
5254
}
53-
if (!g.have_basic_id_info()) {
55+
if ((required & REG_REQUIRE_BASIC_ID) && !g.have_basic_id_info()) {
5456
// if there is no basic ID data stored in the parameters give warning. If basic ID data are streamed to RID device,
5557
// it will store them in the parameters
5658
ret += "ID ";
5759
}
5860

59-
if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
61+
if ((required & REG_REQUIRE_SELF_ID) && (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms)) {
6062
ret += "SELF_ID ";
6163
}
6264

63-
if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
65+
if ((required & REG_REQUIRE_OPERATOR_ID) && (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms)) {
6466
ret += "OP_ID ";
6567
}
6668

67-
if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
69+
if ((required & REG_REQUIRE_SYSTEM) && (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms)) {
6870
// we use location age limit for system as the operator location needs to come in as fast
6971
// as the vehicle location for FAA standard
7072
ret += "SYS ";
7173
}
7274

73-
if (location.latitude == 0 && location.longitude == 0) {
75+
if ((required & REG_REQUIRE_LOC) && (location.latitude == 0 && location.longitude == 0)) {
7476
ret += "LOC ";
7577
}
7678

77-
if (system.operator_latitude == 0 && system.operator_longitude == 0) {
79+
if ((required & REG_REQUIRE_OPERATOR_LOC) && (system.operator_latitude == 0 && system.operator_longitude == 0)) {
7880
ret += "OP_LOC ";
7981
}
8082

0 commit comments

Comments
 (0)