parameters.cpp 14 KB

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