parameters.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519
  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. }
  141. void Parameters::Param::set_int8(int8_t v) const
  142. {
  143. auto *p = (int8_t *)ptr;
  144. *p = v;
  145. nvs_set_i8(handle, name, *p);
  146. }
  147. void Parameters::Param::set_uint32(uint32_t v) const
  148. {
  149. auto *p = (uint32_t *)ptr;
  150. *p = v;
  151. nvs_set_u32(handle, name, *p);
  152. }
  153. void Parameters::Param::set_float(float v) const
  154. {
  155. auto *p = (float *)ptr;
  156. *p = v;
  157. union {
  158. float f;
  159. uint32_t u32;
  160. } u;
  161. u.f = v;
  162. nvs_set_u32(handle, name, u.u32);
  163. }
  164. void Parameters::Param::set_char20(const char *v) const
  165. {
  166. if (min_len > 0 && strlen(v) < min_len) {
  167. return;
  168. }
  169. memset((void*)ptr, 0, 21);
  170. strncpy((char *)ptr, v, 20);
  171. nvs_set_str(handle, name, v);
  172. }
  173. void Parameters::Param::set_char64(const char *v) const
  174. {
  175. if (min_len > 0 && strlen(v) < min_len) {
  176. return;
  177. }
  178. memset((void*)ptr, 0, 65);
  179. strncpy((char *)ptr, v, 64);
  180. nvs_set_str(handle, name, v);
  181. }
  182. uint8_t Parameters::Param::get_uint8() const
  183. {
  184. const auto *p = (const uint8_t *)ptr;
  185. return *p;
  186. }
  187. int8_t Parameters::Param::get_int8() const
  188. {
  189. const auto *p = (const int8_t *)ptr;
  190. return *p;
  191. }
  192. uint32_t Parameters::Param::get_uint32() const
  193. {
  194. const auto *p = (const uint32_t *)ptr;
  195. return *p;
  196. }
  197. float Parameters::Param::get_float() const
  198. {
  199. const auto *p = (const float *)ptr;
  200. return *p;
  201. }
  202. const char *Parameters::Param::get_char20() const
  203. {
  204. const char *p = (const char *)ptr;
  205. return p;
  206. }
  207. const char *Parameters::Param::get_char64() const
  208. {
  209. const char *p = (const char *)ptr;
  210. return p;
  211. }
  212. /*
  213. get parameter as a float
  214. */
  215. bool Parameters::Param::get_as_float(float &v) const
  216. {
  217. switch (ptype) {
  218. case ParamType::UINT8:
  219. v = float(get_uint8());
  220. break;
  221. case ParamType::INT8:
  222. v = float(get_int8());
  223. break;
  224. case ParamType::UINT32:
  225. v = float(get_uint32());
  226. break;
  227. case ParamType::FLOAT:
  228. v = get_float();
  229. break;
  230. default:
  231. return false;
  232. }
  233. return true;
  234. }
  235. /*
  236. set parameter from a float
  237. */
  238. void Parameters::Param::set_as_float(float v) const
  239. {
  240. switch (ptype) {
  241. case ParamType::UINT8:
  242. set_uint8(uint8_t(v));
  243. break;
  244. case ParamType::INT8:
  245. set_int8(int8_t(v));
  246. break;
  247. case ParamType::UINT32:
  248. set_uint32(uint32_t(v));
  249. break;
  250. case ParamType::FLOAT:
  251. set_float(v);
  252. break;
  253. }
  254. }
  255. /*
  256. load defaults from parameter table
  257. */
  258. void Parameters::load_defaults(void)
  259. {
  260. for (const auto &p : params) {
  261. switch (p.ptype) {
  262. case ParamType::UINT8:
  263. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  264. break;
  265. case ParamType::INT8:
  266. *(int8_t *)p.ptr = int8_t(p.default_value);
  267. break;
  268. case ParamType::UINT32:
  269. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  270. break;
  271. case ParamType::FLOAT:
  272. *(float *)p.ptr = p.default_value;
  273. break;
  274. }
  275. }
  276. }
  277. /*
  278. set to factory defaults from parameter table
  279. */
  280. void Parameters::reset_to_defaults(void)
  281. {
  282. for (const auto &p : params) {
  283. switch (p.ptype) {
  284. case ParamType::UINT8:
  285. p.set_uint32(uint8_t(p.default_value));
  286. break;
  287. case ParamType::UINT32:
  288. p.set_uint32(uint32_t(p.default_value));
  289. break;
  290. case ParamType::FLOAT:
  291. p.set_float(float(p.default_value));
  292. break;
  293. case ParamType::CHAR20: {
  294. p.set_char20("");
  295. break;
  296. }
  297. case ParamType::CHAR64: {
  298. p.set_char64("");
  299. break;
  300. }
  301. }
  302. }
  303. }
  304. void Parameters::init(void)
  305. {
  306. load_defaults();
  307. if (nvs_flash_init() != ESP_OK ||
  308. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  309. Serial.printf("NVS init failed\n");
  310. }
  311. // load values from NVS
  312. for (const auto &p : params) {
  313. switch (p.ptype) {
  314. case ParamType::UINT8:
  315. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  316. break;
  317. case ParamType::INT8:
  318. nvs_get_i8(handle, p.name, (int8_t *)p.ptr);
  319. break;
  320. case ParamType::UINT32:
  321. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  322. break;
  323. case ParamType::FLOAT:
  324. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  325. break;
  326. case ParamType::CHAR20: {
  327. size_t len = 21;
  328. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  329. break;
  330. }
  331. case ParamType::CHAR64: {
  332. size_t len = 65;
  333. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  334. break;
  335. }
  336. }
  337. }
  338. if (strlen(g.wifi_ssid) == 0) {
  339. uint8_t mac[6] {};
  340. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  341. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  342. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  343. }
  344. if (g.to_factory_defaults == 1) {
  345. reset_to_defaults(); //save to NVS
  346. load_defaults();
  347. set_by_name_uint8("to_factory_defaults", 0);
  348. }
  349. if (g.done_init == 0) {
  350. set_by_name_uint8("DONE_INIT", 1);
  351. // setup public keys
  352. set_by_name_char64("PUBLIC_KEY1", ROMFS::find_string("public_keys/ArduPilot_public_key1.dat"));
  353. set_by_name_char64("PUBLIC_KEY2", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  354. #if defined(BOARD_BLUEMARK_DB200) || defined(BOARD_BLUEMARK_DB110) || defined(BOARD_BLUEMARK_DB202) || defined(BOARD_BLUEMARK_DB210) || defined(BOARD_BLUEMARK_DB203)
  355. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/BlueMark_public_key1.dat"));
  356. #else
  357. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/ArduPilot_public_key3.dat"));
  358. #endif
  359. }
  360. }
  361. /*
  362. check if BasicID info is filled in with parameters
  363. */
  364. bool Parameters::have_basic_id_info(void) const
  365. {
  366. return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
  367. }
  368. bool Parameters::have_basic_id_2_info(void) const
  369. {
  370. return strlen(g.uas_id_2) > 0 && g.id_type_2 > 0 && g.ua_type_2 > 0;
  371. }
  372. bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
  373. {
  374. const auto *f = find(name);
  375. if (!f) {
  376. return false;
  377. }
  378. f->set_uint8(v);
  379. return true;
  380. }
  381. bool Parameters::set_by_name_int8(const char *name, int8_t v)
  382. {
  383. const auto *f = find(name);
  384. if (!f) {
  385. return false;
  386. }
  387. f->set_int8(v);
  388. return true;
  389. }
  390. bool Parameters::set_by_name_char64(const char *name, const char *s)
  391. {
  392. const auto *f = find(name);
  393. if (!f) {
  394. return false;
  395. }
  396. f->set_char64(s);
  397. return true;
  398. }
  399. bool Parameters::set_by_name_string(const char *name, const char *s)
  400. {
  401. const auto *f = find(name);
  402. if (!f) {
  403. return false;
  404. }
  405. switch (f->ptype) {
  406. case ParamType::UINT8:
  407. f->set_uint8(uint8_t(strtoul(s, nullptr, 0)));
  408. return true;
  409. case ParamType::INT8:
  410. f->set_int8(int8_t(strtoul(s, nullptr, 0)));
  411. return true;
  412. case ParamType::UINT32:
  413. f->set_uint32(strtoul(s, nullptr, 0));
  414. return true;
  415. case ParamType::FLOAT:
  416. f->set_float(atof(s));
  417. return true;
  418. case ParamType::CHAR20:
  419. f->set_char20(s);
  420. return true;
  421. case ParamType::CHAR64:
  422. f->set_char64(s);
  423. return true;
  424. }
  425. return false;
  426. }
  427. /*
  428. return a public key
  429. */
  430. bool Parameters::get_public_key(uint8_t i, uint8_t key[32]) const
  431. {
  432. if (i >= MAX_PUBLIC_KEYS) {
  433. return false;
  434. }
  435. const char *b64_key = g.public_keys[i].b64_key;
  436. const char *ktype = "PUBLIC_KEYV1:";
  437. if (strncmp(b64_key, ktype, strlen(ktype)) != 0) {
  438. return false;
  439. }
  440. b64_key += strlen(ktype);
  441. int32_t out_len = base64_decode(b64_key, key, 32);
  442. if (out_len != 32) {
  443. return false;
  444. }
  445. return true;
  446. }
  447. bool Parameters::no_public_keys(void) const
  448. {
  449. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  450. uint8_t key[32];
  451. if (get_public_key(i, key)) {
  452. return false;
  453. }
  454. }
  455. return true;
  456. }
  457. bool Parameters::set_public_key(uint8_t i, const uint8_t key[32])
  458. {
  459. if (i >= MAX_PUBLIC_KEYS) {
  460. return false;
  461. }
  462. char *s = base64_encode(key, PUBLIC_KEY_LEN);
  463. if (s == nullptr) {
  464. return false;
  465. }
  466. char name[] = "PUBLIC_KEYx";
  467. name[strlen(name)-2] = '1'+i;
  468. bool ret = set_by_name_char64(name, s);
  469. delete[] s;
  470. return ret;
  471. }
  472. bool Parameters::remove_public_key(uint8_t i)
  473. {
  474. if (i >= MAX_PUBLIC_KEYS) {
  475. return false;
  476. }
  477. char name[] = "PUBLIC_KEYx";
  478. name[strlen(name)-2] = '1'+i;
  479. return set_by_name_char64(name, "");
  480. }