parameters.cpp 11 KB

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