parameters.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185
  1. #include "options.h"
  2. #include <Arduino.h>
  3. #include "parameters.h"
  4. #include <nvs_flash.h>
  5. #include <string.h>
  6. Parameters g;
  7. static nvs_handle handle;
  8. const Parameters::Param Parameters::params[] = {
  9. { "LOCK_LEVEL", Parameters::ParamType::UINT8, (const void*)&g.lock_level, 0, 0, 2 },
  10. { "CAN_NODE", Parameters::ParamType::UINT8, (const void*)&g.can_node, 0, 0, 127 },
  11. { "UAS_ID", Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0], 0, 0, 0 },
  12. { "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 57600, 9600, 921600 },
  13. { "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 },
  14. { "BT4_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt4_rate, 1, 0, 5 },
  15. { "BT5_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt5_rate, 1, 0, 5 },
  16. { "WEBSERVER_ENABLE", Parameters::ParamType::UINT8, (const void*)&g.webserver_enable, 1, 0, 1 },
  17. { "WIFI_SSID", Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, },
  18. { "WIFI_PASSWORD", Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, 0, 0, 0, PARAM_FLAG_HIDDEN },
  19. { "BCAST_POWERUP", Parameters::ParamType::UINT8, (const void*)&g.bcast_powerup, 1, 0, 1 },
  20. { "PUBLIC_KEY1", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[0], },
  21. { "PUBLIC_KEY2", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[1], },
  22. { "PUBLIC_KEY3", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[2], },
  23. { "PUBLIC_KEY4", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[3], },
  24. { "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
  25. { "", Parameters::ParamType::NONE, nullptr, },
  26. };
  27. /*
  28. find by name
  29. */
  30. const Parameters::Param *Parameters::find(const char *name)
  31. {
  32. for (const auto &p : params) {
  33. if (strcmp(name, p.name) == 0) {
  34. return &p;
  35. }
  36. }
  37. return nullptr;
  38. }
  39. /*
  40. find by index
  41. */
  42. const Parameters::Param *Parameters::find_by_index(uint16_t index)
  43. {
  44. if (index >= (sizeof(params)/sizeof(params[0])-1)) {
  45. return nullptr;
  46. }
  47. return &params[index];
  48. }
  49. void Parameters::Param::set_uint8(uint8_t v) const
  50. {
  51. auto *p = (uint8_t *)ptr;
  52. *p = v;
  53. nvs_set_u8(handle, name, *p);
  54. }
  55. void Parameters::Param::set_uint32(uint32_t v) const
  56. {
  57. auto *p = (uint32_t *)ptr;
  58. *p = v;
  59. nvs_set_u32(handle, name, *p);
  60. }
  61. void Parameters::Param::set_float(float v) const
  62. {
  63. auto *p = (float *)ptr;
  64. *p = v;
  65. union {
  66. float f;
  67. uint32_t u32;
  68. } u;
  69. u.f = v;
  70. nvs_set_u32(handle, name, u.u32);
  71. }
  72. void Parameters::Param::set_char20(const char *v) const
  73. {
  74. memset((void*)ptr, 0, 21);
  75. strncpy((char *)ptr, v, 20);
  76. nvs_set_str(handle, name, v);
  77. }
  78. void Parameters::Param::set_char64(const char *v) const
  79. {
  80. memset((void*)ptr, 0, 65);
  81. strncpy((char *)ptr, v, 64);
  82. nvs_set_str(handle, name, v);
  83. }
  84. uint8_t Parameters::Param::get_uint8() const
  85. {
  86. const auto *p = (const uint8_t *)ptr;
  87. return *p;
  88. }
  89. uint32_t Parameters::Param::get_uint32() const
  90. {
  91. const auto *p = (const uint32_t *)ptr;
  92. return *p;
  93. }
  94. float Parameters::Param::get_float() const
  95. {
  96. const auto *p = (const float *)ptr;
  97. return *p;
  98. }
  99. const char *Parameters::Param::get_char20() const
  100. {
  101. const char *p = (const char *)ptr;
  102. return p;
  103. }
  104. const char *Parameters::Param::get_char64() const
  105. {
  106. const char *p = (const char *)ptr;
  107. return p;
  108. }
  109. /*
  110. load defaults from parameter table
  111. */
  112. void Parameters::load_defaults(void)
  113. {
  114. for (const auto &p : params) {
  115. switch (p.ptype) {
  116. case ParamType::UINT8:
  117. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  118. break;
  119. case ParamType::UINT32:
  120. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  121. break;
  122. case ParamType::FLOAT:
  123. *(float *)p.ptr = p.default_value;
  124. break;
  125. }
  126. }
  127. }
  128. void Parameters::init(void)
  129. {
  130. load_defaults();
  131. if (nvs_flash_init() != ESP_OK ||
  132. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  133. Serial.printf("NVS init failed\n");
  134. }
  135. // load values from NVS
  136. for (const auto &p : params) {
  137. switch (p.ptype) {
  138. case ParamType::UINT8:
  139. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  140. break;
  141. case ParamType::UINT32:
  142. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  143. break;
  144. case ParamType::FLOAT:
  145. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  146. break;
  147. case ParamType::CHAR20: {
  148. size_t len = 21;
  149. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  150. break;
  151. }
  152. case ParamType::CHAR64: {
  153. size_t len = 65;
  154. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  155. break;
  156. }
  157. }
  158. }
  159. if (strlen(g.wifi_ssid) == 0) {
  160. uint8_t mac[6] {};
  161. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  162. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  163. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  164. }
  165. }