parameters.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496
  1. #include "options.h"
  2. #include <Arduino.h>
  3. #include "parameters.h"
  4. #include <nvs_flash.h>
  5. #include <string.h>
  6. #include "romfs.h"
  7. #include "util.h"
  8. Parameters g;
  9. static nvs_handle handle;
  10. const Parameters::Param Parameters::params[] = {
  11. { "LOCK_LEVEL", Parameters::ParamType::INT8, (const void*)&g.lock_level, 0, -1, 2 },
  12. { "CAN_NODE", Parameters::ParamType::UINT8, (const void*)&g.can_node, 0, 0, 127 },
  13. { "UAS_TYPE", Parameters::ParamType::UINT8, (const void*)&g.ua_type, 0, 0, 15 },
  14. { "UAS_ID_TYPE", Parameters::ParamType::UINT8, (const void*)&g.id_type, 0, 0, 4 },
  15. { "UAS_ID", Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0], 0, 0, 0 },
  16. { "UAS_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.ua_type_2, 0, 0, 15 },
  17. { "UAS_ID_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.id_type_2, 0, 0, 4 },
  18. { "UAS_ID_2", Parameters::ParamType::CHAR20, (const void*)&g.uas_id_2[0], 0, 0, 0 },
  19. { "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 57600, 9600, 921600 },
  20. { "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 },
  21. { "WIFI_BCN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_beacon_rate, 0, 0, 5 },
  22. { "WIFI_POWER", Parameters::ParamType::FLOAT, (const void*)&g.wifi_power, 20, 2, 20 },
  23. { "BT4_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt4_rate, 1, 0, 5 },
  24. { "BT4_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt4_power, 18, -27, 18 },
  25. { "BT5_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt5_rate, 1, 0, 5 },
  26. { "BT5_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt5_power, 18, -27, 18 },
  27. { "WEBSERVER_EN", Parameters::ParamType::UINT8, (const void*)&g.webserver_enable, 1, 0, 1 },
  28. { "WIFI_SSID", Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, },
  29. { "WIFI_PASSWORD", Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, 0, 0, 0, PARAM_FLAG_PASSWORD, 8 },
  30. { "WIFI_CHANNEL", Parameters::ParamType::UINT8, (const void*)&g.wifi_channel, 6, 1, 13 },
  31. { "BCAST_POWERUP", Parameters::ParamType::UINT8, (const void*)&g.bcast_powerup, 1, 0, 1 },
  32. { "PUBLIC_KEY1", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[0], },
  33. { "PUBLIC_KEY2", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[1], },
  34. { "PUBLIC_KEY3", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[2], },
  35. { "PUBLIC_KEY4", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[3], },
  36. { "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
  37. { "MAVLINK_SYSID", Parameters::ParamType::UINT8, (const void*)&g.mavlink_sysid, 0, 0, 254 },
  38. { "OPTIONS", Parameters::ParamType::UINT8, (const void*)&g.options, 0, 0, 254 },
  39. { "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.
  40. { "DONE_INIT", Parameters::ParamType::UINT8, (const void*)&g.done_init, 0, 0, 0, PARAM_FLAG_HIDDEN},
  41. { "", Parameters::ParamType::NONE, nullptr, },
  42. };
  43. /*
  44. get count of parameters capable of being converted to load
  45. */
  46. uint16_t Parameters::param_count_float(void)
  47. {
  48. uint16_t count = 0;
  49. for (const auto &p : params) {
  50. if (p.flags & PARAM_FLAG_HIDDEN) {
  51. continue;
  52. }
  53. switch (p.ptype) {
  54. case ParamType::UINT8:
  55. case ParamType::INT8:
  56. case ParamType::UINT32:
  57. case ParamType::FLOAT:
  58. count++;
  59. break;
  60. }
  61. }
  62. // remove 1 for DONE_INIT
  63. return count-1;
  64. }
  65. /*
  66. get index of parameter counting only those capable of representation as float
  67. */
  68. int16_t Parameters::param_index_float(const Parameters::Param *f)
  69. {
  70. uint16_t count = 0;
  71. for (const auto &p : params) {
  72. if (p.flags & PARAM_FLAG_HIDDEN) {
  73. continue;
  74. }
  75. switch (p.ptype) {
  76. case ParamType::UINT8:
  77. case ParamType::INT8:
  78. case ParamType::UINT32:
  79. case ParamType::FLOAT:
  80. if (&p == f) {
  81. return count;
  82. }
  83. count++;
  84. break;
  85. }
  86. }
  87. return -1;
  88. }
  89. /*
  90. find by name
  91. */
  92. const Parameters::Param *Parameters::find(const char *name)
  93. {
  94. for (const auto &p : params) {
  95. if (strcmp(name, p.name) == 0) {
  96. return &p;
  97. }
  98. }
  99. return nullptr;
  100. }
  101. /*
  102. find by index
  103. */
  104. const Parameters::Param *Parameters::find_by_index(uint16_t index)
  105. {
  106. if (index >= ARRAY_SIZE(params)-2) {
  107. return nullptr;
  108. }
  109. return &params[index];
  110. }
  111. /*
  112. find by index
  113. */
  114. const Parameters::Param *Parameters::find_by_index_float(uint16_t index)
  115. {
  116. uint16_t count = 0;
  117. for (const auto &p : params) {
  118. if (p.flags & PARAM_FLAG_HIDDEN) {
  119. continue;
  120. }
  121. switch (p.ptype) {
  122. case ParamType::UINT8:
  123. case ParamType::INT8:
  124. case ParamType::UINT32:
  125. case ParamType::FLOAT:
  126. if (index == count) {
  127. return &p;
  128. }
  129. count++;
  130. break;
  131. }
  132. }
  133. return nullptr;
  134. }
  135. void Parameters::Param::set_uint8(uint8_t v) const
  136. {
  137. auto *p = (uint8_t *)ptr;
  138. *p = v;
  139. nvs_set_u8(handle, name, *p);
  140. if (strcmp(name, "TO_DEFAULTS") == 0) {
  141. if (v == 1) {
  142. esp_restart(); //reset, so the init function will set it to factory defaults
  143. }
  144. }
  145. }
  146. void Parameters::Param::set_int8(int8_t v) const
  147. {
  148. auto *p = (int8_t *)ptr;
  149. *p = v;
  150. nvs_set_i8(handle, name, *p);
  151. }
  152. void Parameters::Param::set_uint32(uint32_t v) const
  153. {
  154. auto *p = (uint32_t *)ptr;
  155. *p = v;
  156. nvs_set_u32(handle, name, *p);
  157. }
  158. void Parameters::Param::set_float(float v) const
  159. {
  160. auto *p = (float *)ptr;
  161. *p = v;
  162. union {
  163. float f;
  164. uint32_t u32;
  165. } u;
  166. u.f = v;
  167. nvs_set_u32(handle, name, u.u32);
  168. }
  169. void Parameters::Param::set_char20(const char *v) const
  170. {
  171. if (min_len > 0 && strlen(v) < min_len) {
  172. return;
  173. }
  174. memset((void*)ptr, 0, 21);
  175. strncpy((char *)ptr, v, 20);
  176. nvs_set_str(handle, name, v);
  177. }
  178. void Parameters::Param::set_char64(const char *v) const
  179. {
  180. if (min_len > 0 && strlen(v) < min_len) {
  181. return;
  182. }
  183. memset((void*)ptr, 0, 65);
  184. strncpy((char *)ptr, v, 64);
  185. nvs_set_str(handle, name, v);
  186. }
  187. uint8_t Parameters::Param::get_uint8() const
  188. {
  189. const auto *p = (const uint8_t *)ptr;
  190. return *p;
  191. }
  192. int8_t Parameters::Param::get_int8() const
  193. {
  194. const auto *p = (const int8_t *)ptr;
  195. return *p;
  196. }
  197. uint32_t Parameters::Param::get_uint32() const
  198. {
  199. const auto *p = (const uint32_t *)ptr;
  200. return *p;
  201. }
  202. float Parameters::Param::get_float() const
  203. {
  204. const auto *p = (const float *)ptr;
  205. return *p;
  206. }
  207. const char *Parameters::Param::get_char20() const
  208. {
  209. const char *p = (const char *)ptr;
  210. return p;
  211. }
  212. const char *Parameters::Param::get_char64() const
  213. {
  214. const char *p = (const char *)ptr;
  215. return p;
  216. }
  217. /*
  218. get parameter as a float
  219. */
  220. bool Parameters::Param::get_as_float(float &v) const
  221. {
  222. switch (ptype) {
  223. case ParamType::UINT8:
  224. v = float(get_uint8());
  225. break;
  226. case ParamType::INT8:
  227. v = float(get_int8());
  228. break;
  229. case ParamType::UINT32:
  230. v = float(get_uint32());
  231. break;
  232. case ParamType::FLOAT:
  233. v = get_float();
  234. break;
  235. default:
  236. return false;
  237. }
  238. return true;
  239. }
  240. /*
  241. set parameter from a float
  242. */
  243. void Parameters::Param::set_as_float(float v) const
  244. {
  245. switch (ptype) {
  246. case ParamType::UINT8:
  247. set_uint8(uint8_t(v));
  248. break;
  249. case ParamType::INT8:
  250. set_int8(int8_t(v));
  251. break;
  252. case ParamType::UINT32:
  253. set_uint32(uint32_t(v));
  254. break;
  255. case ParamType::FLOAT:
  256. set_float(v);
  257. break;
  258. }
  259. }
  260. /*
  261. load defaults from parameter table
  262. */
  263. void Parameters::load_defaults(void)
  264. {
  265. for (const auto &p : params) {
  266. switch (p.ptype) {
  267. case ParamType::UINT8:
  268. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  269. break;
  270. case ParamType::INT8:
  271. *(int8_t *)p.ptr = int8_t(p.default_value);
  272. break;
  273. case ParamType::UINT32:
  274. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  275. break;
  276. case ParamType::FLOAT:
  277. *(float *)p.ptr = p.default_value;
  278. break;
  279. }
  280. }
  281. }
  282. void Parameters::init(void)
  283. {
  284. load_defaults();
  285. if (nvs_flash_init() != ESP_OK ||
  286. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  287. Serial.printf("NVS init failed\n");
  288. }
  289. // load values from NVS
  290. for (const auto &p : params) {
  291. switch (p.ptype) {
  292. case ParamType::UINT8:
  293. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  294. break;
  295. case ParamType::INT8:
  296. nvs_get_i8(handle, p.name, (int8_t *)p.ptr);
  297. break;
  298. case ParamType::UINT32:
  299. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  300. break;
  301. case ParamType::FLOAT:
  302. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  303. break;
  304. case ParamType::CHAR20: {
  305. size_t len = 21;
  306. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  307. break;
  308. }
  309. case ParamType::CHAR64: {
  310. size_t len = 65;
  311. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  312. break;
  313. }
  314. }
  315. }
  316. if (strlen(g.wifi_ssid) == 0) {
  317. uint8_t mac[6] {};
  318. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  319. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  320. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  321. }
  322. if (g.to_factory_defaults == 1) {
  323. reset_to_defaults(); //save to NVS
  324. load_defaults();
  325. set_by_name_uint8("TO_DEFAULTS", 0);
  326. }
  327. if (g.done_init == 0) {
  328. set_by_name_uint8("DONE_INIT", 1);
  329. // setup public keys
  330. set_by_name_char64("PUBLIC_KEY1", ROMFS::find_string("public_keys/ArduPilot_public_key1.dat"));
  331. set_by_name_char64("PUBLIC_KEY2", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  332. #if defined(BOARD_BLUEMARK_DB200) || defined(BOARD_BLUEMARK_DB110) || defined(BOARD_BLUEMARK_DB202) || defined(BOARD_BLUEMARK_DB210) || defined(BOARD_BLUEMARK_DB203)
  333. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/BlueMark_public_key1.dat"));
  334. #else
  335. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/ArduPilot_public_key3.dat"));
  336. #endif
  337. }
  338. }
  339. /*
  340. check if BasicID info is filled in with parameters
  341. */
  342. bool Parameters::have_basic_id_info(void) const
  343. {
  344. return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
  345. }
  346. bool Parameters::have_basic_id_2_info(void) const
  347. {
  348. return strlen(g.uas_id_2) > 0 && g.id_type_2 > 0 && g.ua_type_2 > 0;
  349. }
  350. bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
  351. {
  352. const auto *f = find(name);
  353. if (!f) {
  354. return false;
  355. }
  356. f->set_uint8(v);
  357. return true;
  358. }
  359. bool Parameters::set_by_name_int8(const char *name, int8_t v)
  360. {
  361. const auto *f = find(name);
  362. if (!f) {
  363. return false;
  364. }
  365. f->set_int8(v);
  366. return true;
  367. }
  368. bool Parameters::set_by_name_char64(const char *name, const char *s)
  369. {
  370. const auto *f = find(name);
  371. if (!f) {
  372. return false;
  373. }
  374. f->set_char64(s);
  375. return true;
  376. }
  377. bool Parameters::set_by_name_string(const char *name, const char *s)
  378. {
  379. const auto *f = find(name);
  380. if (!f) {
  381. return false;
  382. }
  383. switch (f->ptype) {
  384. case ParamType::UINT8:
  385. f->set_uint8(uint8_t(strtoul(s, nullptr, 0)));
  386. return true;
  387. case ParamType::INT8:
  388. f->set_int8(int8_t(strtoul(s, nullptr, 0)));
  389. return true;
  390. case ParamType::UINT32:
  391. f->set_uint32(strtoul(s, nullptr, 0));
  392. return true;
  393. case ParamType::FLOAT:
  394. f->set_float(atof(s));
  395. return true;
  396. case ParamType::CHAR20:
  397. f->set_char20(s);
  398. return true;
  399. case ParamType::CHAR64:
  400. f->set_char64(s);
  401. return true;
  402. }
  403. return false;
  404. }
  405. /*
  406. return a public key
  407. */
  408. bool Parameters::get_public_key(uint8_t i, uint8_t key[32]) const
  409. {
  410. if (i >= MAX_PUBLIC_KEYS) {
  411. return false;
  412. }
  413. const char *b64_key = g.public_keys[i].b64_key;
  414. const char *ktype = "PUBLIC_KEYV1:";
  415. if (strncmp(b64_key, ktype, strlen(ktype)) != 0) {
  416. return false;
  417. }
  418. b64_key += strlen(ktype);
  419. int32_t out_len = base64_decode(b64_key, key, 32);
  420. if (out_len != 32) {
  421. return false;
  422. }
  423. return true;
  424. }
  425. bool Parameters::no_public_keys(void) const
  426. {
  427. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  428. uint8_t key[32];
  429. if (get_public_key(i, key)) {
  430. return false;
  431. }
  432. }
  433. return true;
  434. }
  435. bool Parameters::set_public_key(uint8_t i, const uint8_t key[32])
  436. {
  437. if (i >= MAX_PUBLIC_KEYS) {
  438. return false;
  439. }
  440. char *s = base64_encode(key, PUBLIC_KEY_LEN);
  441. if (s == nullptr) {
  442. return false;
  443. }
  444. char name[] = "PUBLIC_KEYx";
  445. name[strlen(name)-2] = '1'+i;
  446. bool ret = set_by_name_char64(name, s);
  447. delete[] s;
  448. return ret;
  449. }
  450. bool Parameters::remove_public_key(uint8_t i)
  451. {
  452. if (i >= MAX_PUBLIC_KEYS) {
  453. return false;
  454. }
  455. char name[] = "PUBLIC_KEYx";
  456. name[strlen(name)-2] = '1'+i;
  457. return set_by_name_char64(name, "");
  458. }