parameters.cpp 14 KB

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