parameters.cpp 12 KB

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