parameters.cpp 6.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234
  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. Parameters g;
  8. static nvs_handle handle;
  9. const Parameters::Param Parameters::params[] = {
  10. { "LOCK_LEVEL", Parameters::ParamType::UINT8, (const void*)&g.lock_level, 0, 0, 2 },
  11. { "CAN_NODE", Parameters::ParamType::UINT8, (const void*)&g.can_node, 0, 0, 127 },
  12. { "UA_TYPE", Parameters::ParamType::UINT8, (const void*)&g.ua_type, 0, 0, 15 },
  13. { "ID_TYPE", Parameters::ParamType::UINT8, (const void*)&g.id_type, 0, 0, 4 },
  14. { "UAS_ID", Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0], 0, 0, 0 },
  15. { "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 57600, 9600, 921600 },
  16. { "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 },
  17. { "WIFI_POWER", Parameters::ParamType::FLOAT, (const void*)&g.wifi_power, 20, 2, 20 },
  18. { "BT4_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt4_rate, 1, 0, 5 },
  19. { "BT4_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt4_power, 18, -27, 18 },
  20. { "BT5_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt5_rate, 1, 0, 5 },
  21. { "BT5_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt5_power, 18, -27, 18 },
  22. { "WEBSERVER_ENABLE", Parameters::ParamType::UINT8, (const void*)&g.webserver_enable, 1, 0, 1 },
  23. { "WIFI_SSID", Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, },
  24. { "WIFI_PASSWORD", Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, 0, 0, 0, PARAM_FLAG_PASSWORD, 8 },
  25. { "BCAST_POWERUP", Parameters::ParamType::UINT8, (const void*)&g.bcast_powerup, 1, 0, 1 },
  26. { "PUBLIC_KEY1", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[0], },
  27. { "PUBLIC_KEY2", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[1], },
  28. { "PUBLIC_KEY3", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[2], },
  29. { "PUBLIC_KEY4", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[3], },
  30. { "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
  31. { "DONE_INIT", Parameters::ParamType::UINT8, (const void*)&g.done_init, 0, 0, 0, PARAM_FLAG_HIDDEN},
  32. { "", Parameters::ParamType::NONE, nullptr, },
  33. };
  34. /*
  35. find by name
  36. */
  37. const Parameters::Param *Parameters::find(const char *name)
  38. {
  39. for (const auto &p : params) {
  40. if (strcmp(name, p.name) == 0) {
  41. return &p;
  42. }
  43. }
  44. return nullptr;
  45. }
  46. /*
  47. find by index
  48. */
  49. const Parameters::Param *Parameters::find_by_index(uint16_t index)
  50. {
  51. if (index >= (sizeof(params)/sizeof(params[0])-1)) {
  52. return nullptr;
  53. }
  54. return &params[index];
  55. }
  56. void Parameters::Param::set_uint8(uint8_t v) const
  57. {
  58. auto *p = (uint8_t *)ptr;
  59. *p = v;
  60. nvs_set_u8(handle, name, *p);
  61. }
  62. void Parameters::Param::set_uint32(uint32_t v) const
  63. {
  64. auto *p = (uint32_t *)ptr;
  65. *p = v;
  66. nvs_set_u32(handle, name, *p);
  67. }
  68. void Parameters::Param::set_float(float v) const
  69. {
  70. auto *p = (float *)ptr;
  71. *p = v;
  72. union {
  73. float f;
  74. uint32_t u32;
  75. } u;
  76. u.f = v;
  77. nvs_set_u32(handle, name, u.u32);
  78. }
  79. void Parameters::Param::set_char20(const char *v) const
  80. {
  81. if (min_len > 0 && strlen(v) < min_len) {
  82. return;
  83. }
  84. memset((void*)ptr, 0, 21);
  85. strncpy((char *)ptr, v, 20);
  86. nvs_set_str(handle, name, v);
  87. }
  88. void Parameters::Param::set_char64(const char *v) const
  89. {
  90. if (min_len > 0 && strlen(v) < min_len) {
  91. return;
  92. }
  93. memset((void*)ptr, 0, 65);
  94. strncpy((char *)ptr, v, 64);
  95. nvs_set_str(handle, name, v);
  96. }
  97. uint8_t Parameters::Param::get_uint8() const
  98. {
  99. const auto *p = (const uint8_t *)ptr;
  100. return *p;
  101. }
  102. uint32_t Parameters::Param::get_uint32() const
  103. {
  104. const auto *p = (const uint32_t *)ptr;
  105. return *p;
  106. }
  107. float Parameters::Param::get_float() const
  108. {
  109. const auto *p = (const float *)ptr;
  110. return *p;
  111. }
  112. const char *Parameters::Param::get_char20() const
  113. {
  114. const char *p = (const char *)ptr;
  115. return p;
  116. }
  117. const char *Parameters::Param::get_char64() const
  118. {
  119. const char *p = (const char *)ptr;
  120. return p;
  121. }
  122. /*
  123. load defaults from parameter table
  124. */
  125. void Parameters::load_defaults(void)
  126. {
  127. for (const auto &p : params) {
  128. switch (p.ptype) {
  129. case ParamType::UINT8:
  130. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  131. break;
  132. case ParamType::UINT32:
  133. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  134. break;
  135. case ParamType::FLOAT:
  136. *(float *)p.ptr = p.default_value;
  137. break;
  138. }
  139. }
  140. }
  141. void Parameters::init(void)
  142. {
  143. load_defaults();
  144. if (nvs_flash_init() != ESP_OK ||
  145. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  146. Serial.printf("NVS init failed\n");
  147. }
  148. // load values from NVS
  149. for (const auto &p : params) {
  150. switch (p.ptype) {
  151. case ParamType::UINT8:
  152. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  153. break;
  154. case ParamType::UINT32:
  155. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  156. break;
  157. case ParamType::FLOAT:
  158. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  159. break;
  160. case ParamType::CHAR20: {
  161. size_t len = 21;
  162. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  163. break;
  164. }
  165. case ParamType::CHAR64: {
  166. size_t len = 65;
  167. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  168. break;
  169. }
  170. }
  171. }
  172. if (strlen(g.wifi_ssid) == 0) {
  173. uint8_t mac[6] {};
  174. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  175. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  176. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  177. }
  178. if (g.done_init == 0) {
  179. set_by_name_uint8("DONE_INIT", 1);
  180. // setup public keys
  181. set_by_name_char64("PUBLIC_KEY1", ROMFS::find_string("public_keys/ArduPilot_public_key1.dat"));
  182. set_by_name_char64("PUBLIC_KEY2", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  183. set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  184. }
  185. }
  186. /*
  187. check if BasicID info is filled in with parameters
  188. */
  189. bool Parameters::have_basic_id_info(void) const
  190. {
  191. return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
  192. }
  193. bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
  194. {
  195. const auto *f = find(name);
  196. if (!f) {
  197. return false;
  198. }
  199. f->set_uint8(v);
  200. return true;
  201. }
  202. bool Parameters::set_by_name_char64(const char *name, const char *s)
  203. {
  204. const auto *f = find(name);
  205. if (!f) {
  206. return false;
  207. }
  208. f->set_char64(s);
  209. return true;
  210. }