parameters.cpp 11 KB

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