parameters.cpp 13 KB

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