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

store operator ID in parameters #135

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
17 changes: 17 additions & 0 deletions RemoteIDModule/RemoteIDModule.ino
Original file line number Diff line number Diff line change
Expand Up @@ -277,6 +277,23 @@ static void set_data(Transport &t)
UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)operator_id.operator_id_type;
ODID_COPY_STR(UAS_data.OperatorID.OperatorId, operator_id.operator_id);
UAS_data.OperatorIDValid = 1;

//copy to parameters if is not stored yet.
if (strcmp((const char*)g.operator_id, (const char*)operator_id.operator_id) != 0) {
g.set_by_name_uint8("OPERATOR_ID_TYPE", operator_id.operator_id_type);
char operator_id_tmp[ODID_ID_SIZE + 1] {};
ODID_COPY_STR(operator_id_tmp, operator_id.operator_id);
g.set_by_name_string("OPERATOR_ID", operator_id_tmp);
}
}
else
{
if (g.have_operator_id_info()) {
// from parameters
UAS_data.OperatorID.OperatorIdType = (ODID_operatorIdType_t)g.operator_id_type;
ODID_COPY_STR(UAS_data.OperatorID.OperatorId, g.operator_id);
UAS_data.OperatorIDValid = 1;
}
}

// SelfID
Expand Down
8 changes: 8 additions & 0 deletions RemoteIDModule/parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ const Parameters::Param Parameters::params[] = {
{ "UAS_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.ua_type_2, 0, 0, 15 },
{ "UAS_ID_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.id_type_2, 0, 0, 4 },
{ "UAS_ID_2", Parameters::ParamType::CHAR20, (const void*)&g.uas_id_2[0], 0, 0, 0 },
{ "OPERATOR_ID", Parameters::ParamType::CHAR20, (const void*)&g.operator_id[0], 0, 0, 0 },
{ "OPERATOR_ID_TYPE", Parameters::ParamType::UINT8, (const void*)&g.operator_id_type, 0, 0, 0 },
{ "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 57600, 9600, 921600 },
{ "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 },
{ "WIFI_BCN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_beacon_rate, 0, 0, 5 },
Expand Down Expand Up @@ -380,6 +382,12 @@ bool Parameters::have_basic_id_2_info(void) const
return strlen(g.uas_id_2) > 0 && g.id_type_2 > 0 && g.ua_type_2 > 0;
}

bool Parameters::have_operator_id_info(void) const
{
return strlen(g.operator_id) > 0; //at the moment the operator type can only be zero. So no checking on the type.
}


bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
{
const auto *f = find(name);
Expand Down
3 changes: 3 additions & 0 deletions RemoteIDModule/parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ class Parameters {
uint8_t ua_type_2;
uint8_t id_type_2;
char uas_id_2[21] = "ABCD123456789";
char operator_id[21] = "";
uint8_t operator_id_type;
float wifi_nan_rate;
float wifi_beacon_rate;
float wifi_power;
Expand Down Expand Up @@ -85,6 +87,7 @@ class Parameters {

bool have_basic_id_info(void) const;
bool have_basic_id_2_info(void) const;
bool have_operator_id_info(void) const;

bool set_by_name_uint8(const char *name, uint8_t v);
bool set_by_name_int8(const char *name, int8_t v);
Expand Down
Loading