parameters.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293
  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. find by name
  37. */
  38. const Parameters::Param *Parameters::find(const char *name)
  39. {
  40. for (const auto &p : params) {
  41. if (strcmp(name, p.name) == 0) {
  42. return &p;
  43. }
  44. }
  45. return nullptr;
  46. }
  47. /*
  48. find by index
  49. */
  50. const Parameters::Param *Parameters::find_by_index(uint16_t index)
  51. {
  52. if (index >= (sizeof(params)/sizeof(params[0])-1)) {
  53. return nullptr;
  54. }
  55. return &params[index];
  56. }
  57. void Parameters::Param::set_uint8(uint8_t v) const
  58. {
  59. auto *p = (uint8_t *)ptr;
  60. *p = v;
  61. nvs_set_u8(handle, name, *p);
  62. }
  63. void Parameters::Param::set_uint32(uint32_t v) const
  64. {
  65. auto *p = (uint32_t *)ptr;
  66. *p = v;
  67. nvs_set_u32(handle, name, *p);
  68. }
  69. void Parameters::Param::set_float(float v) const
  70. {
  71. auto *p = (float *)ptr;
  72. *p = v;
  73. union {
  74. float f;
  75. uint32_t u32;
  76. } u;
  77. u.f = v;
  78. nvs_set_u32(handle, name, u.u32);
  79. }
  80. void Parameters::Param::set_char20(const char *v) const
  81. {
  82. if (min_len > 0 && strlen(v) < min_len) {
  83. return;
  84. }
  85. memset((void*)ptr, 0, 21);
  86. strncpy((char *)ptr, v, 20);
  87. nvs_set_str(handle, name, v);
  88. }
  89. void Parameters::Param::set_char64(const char *v) const
  90. {
  91. if (min_len > 0 && strlen(v) < min_len) {
  92. return;
  93. }
  94. memset((void*)ptr, 0, 65);
  95. strncpy((char *)ptr, v, 64);
  96. nvs_set_str(handle, name, v);
  97. }
  98. uint8_t Parameters::Param::get_uint8() const
  99. {
  100. const auto *p = (const uint8_t *)ptr;
  101. return *p;
  102. }
  103. uint32_t Parameters::Param::get_uint32() const
  104. {
  105. const auto *p = (const uint32_t *)ptr;
  106. return *p;
  107. }
  108. float Parameters::Param::get_float() const
  109. {
  110. const auto *p = (const float *)ptr;
  111. return *p;
  112. }
  113. const char *Parameters::Param::get_char20() const
  114. {
  115. const char *p = (const char *)ptr;
  116. return p;
  117. }
  118. const char *Parameters::Param::get_char64() const
  119. {
  120. const char *p = (const char *)ptr;
  121. return p;
  122. }
  123. /*
  124. load defaults from parameter table
  125. */
  126. void Parameters::load_defaults(void)
  127. {
  128. for (const auto &p : params) {
  129. switch (p.ptype) {
  130. case ParamType::UINT8:
  131. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  132. break;
  133. case ParamType::UINT32:
  134. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  135. break;
  136. case ParamType::FLOAT:
  137. *(float *)p.ptr = p.default_value;
  138. break;
  139. }
  140. }
  141. }
  142. void Parameters::init(void)
  143. {
  144. load_defaults();
  145. if (nvs_flash_init() != ESP_OK ||
  146. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  147. Serial.printf("NVS init failed\n");
  148. }
  149. // load values from NVS
  150. for (const auto &p : params) {
  151. switch (p.ptype) {
  152. case ParamType::UINT8:
  153. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  154. break;
  155. case ParamType::UINT32:
  156. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  157. break;
  158. case ParamType::FLOAT:
  159. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  160. break;
  161. case ParamType::CHAR20: {
  162. size_t len = 21;
  163. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  164. break;
  165. }
  166. case ParamType::CHAR64: {
  167. size_t len = 65;
  168. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  169. break;
  170. }
  171. }
  172. }
  173. if (strlen(g.wifi_ssid) == 0) {
  174. uint8_t mac[6] {};
  175. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  176. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  177. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  178. }
  179. if (g.done_init == 0) {
  180. set_by_name_uint8("DONE_INIT", 1);
  181. // setup public keys
  182. set_by_name_char64("PUBLIC_KEY1", ROMFS::find_string("public_keys/ArduPilot_public_key1.dat"));
  183. set_by_name_char64("PUBLIC_KEY2", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  184. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  185. }
  186. }
  187. /*
  188. check if BasicID info is filled in with parameters
  189. */
  190. bool Parameters::have_basic_id_info(void) const
  191. {
  192. return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
  193. }
  194. bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
  195. {
  196. const auto *f = find(name);
  197. if (!f) {
  198. return false;
  199. }
  200. f->set_uint8(v);
  201. return true;
  202. }
  203. bool Parameters::set_by_name_char64(const char *name, const char *s)
  204. {
  205. const auto *f = find(name);
  206. if (!f) {
  207. return false;
  208. }
  209. f->set_char64(s);
  210. return true;
  211. }
  212. bool Parameters::set_by_name_string(const char *name, const char *s)
  213. {
  214. const auto *f = find(name);
  215. if (!f) {
  216. return false;
  217. }
  218. switch (f->ptype) {
  219. case ParamType::UINT8:
  220. f->set_uint8(uint8_t(strtoul(s, nullptr, 0)));
  221. return true;
  222. case ParamType::UINT32:
  223. f->set_uint32(strtoul(s, nullptr, 0));
  224. return true;
  225. case ParamType::FLOAT:
  226. f->set_float(atof(s));
  227. return true;
  228. case ParamType::CHAR20:
  229. f->set_char20(s);
  230. return true;
  231. case ParamType::CHAR64:
  232. f->set_char64(s);
  233. return true;
  234. }
  235. return false;
  236. }
  237. /*
  238. return a public key
  239. */
  240. bool Parameters::get_public_key(uint8_t i, uint8_t key[32]) const
  241. {
  242. if (i >= MAX_PUBLIC_KEYS) {
  243. return false;
  244. }
  245. const char *b64_key = g.public_keys[i].b64_key;
  246. const char *ktype = "PUBLIC_KEYV1:";
  247. if (strncmp(b64_key, ktype, strlen(ktype)) != 0) {
  248. return false;
  249. }
  250. b64_key += strlen(ktype);
  251. int32_t out_len = base64_decode(b64_key, key, 32);
  252. if (out_len != 32) {
  253. return false;
  254. }
  255. return true;
  256. }
  257. bool Parameters::no_public_keys(void) const
  258. {
  259. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  260. uint8_t key[32];
  261. if (get_public_key(i, key)) {
  262. return false;
  263. }
  264. }
  265. return true;
  266. }