parameters.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511
  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. // 正常商品lock应该为0 但是需要签名才能进行升级 所以这里默认值给-1
  11. // 默认参数值 参数最小值 参数最大值 对于lock默认值时0 改为-1可以任意web升级固件 不需要签名
  12. const Parameters::Param Parameters::params[] = {
  13. { "LOCK_LEVEL", Parameters::ParamType::INT8, (const void*)&g.lock_level, 0, -1, 2 },
  14. { "CAN_NODE", Parameters::ParamType::UINT8, (const void*)&g.can_node, 100, 0, 127 },
  15. #if defined(PIN_CAN_TERM)
  16. { "CAN_TERMINATE", Parameters::ParamType::UINT8, (const void*)&g.can_term, 0, 0, 1 },
  17. #endif
  18. { "PROTOCOL", Parameters::ParamType::UINT8, (const void*)&g.protocol, 0, 0, 2 }, // 新加
  19. { "UAS_TYPE", Parameters::ParamType::UINT8, (const void*)&g.ua_type, 2, 0, 15 },
  20. { "UAS_ID_TYPE", Parameters::ParamType::UINT8, (const void*)&g.id_type, 1, 0, 4 },
  21. { "UAS_ID", Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0], 0, 0, 0 },
  22. { "UAS_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.ua_type_2, 0, 0, 15 },
  23. { "UAS_ID_TYPE_2", Parameters::ParamType::UINT8, (const void*)&g.id_type_2, 0, 0, 4 },
  24. { "UAS_ID_2", Parameters::ParamType::CHAR20, (const void*)&g.uas_id_2[0], 0, 0, 0 },
  25. { "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 115200, 9600, 921600 },
  26. { "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 },
  27. { "WIFI_BCN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_beacon_rate, 0, 0, 5 },
  28. { "WIFI_POWER", Parameters::ParamType::FLOAT, (const void*)&g.wifi_power, 20, 2, 20 },
  29. { "BT4_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt4_rate, 1, 0, 5 },
  30. { "BT4_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt4_power, 18, -27, 18 },
  31. { "BT5_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt5_rate, 1, 0, 5 },
  32. { "BT5_POWER", Parameters::ParamType::FLOAT, (const void*)&g.bt5_power, 18, -27, 18 },
  33. { "WEBSERVER_EN", Parameters::ParamType::UINT8, (const void*)&g.webserver_enable, 1, 0, 1 },
  34. { "WIFI_SSID", Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, },
  35. { "WIFI_PASSWORD", Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, 0, 0, 0, PARAM_FLAG_PASSWORD, 8 },
  36. { "WIFI_CHANNEL", Parameters::ParamType::UINT8, (const void*)&g.wifi_channel, 6, 1, 13 },
  37. { "BCAST_POWERUP", Parameters::ParamType::UINT8, (const void*)&g.bcast_powerup, 0, 0, 1 },
  38. { "PUBLIC_KEY1", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[0], },
  39. { "PUBLIC_KEY2", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[1], },
  40. { "PUBLIC_KEY3", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[2], },
  41. { "PUBLIC_KEY4", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[3], },
  42. { "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], },
  43. { "MAVLINK_SYSID", Parameters::ParamType::UINT8, (const void*)&g.mavlink_sysid, 0, 0, 254 },
  44. { "OPTIONS", Parameters::ParamType::UINT8, (const void*)&g.options, 2, 0, 254 },
  45. { "TO_DEFAULTS", Parameters::ParamType::UINT8, (const void*)&g.to_factory_defaults, 0, 0, 1 }, //if set to 1, reset to factory defaults and make 0.
  46. { "DONE_INIT", Parameters::ParamType::UINT8, (const void*)&g.done_init, 0, 0, 0, PARAM_FLAG_HIDDEN},
  47. { "", Parameters::ParamType::NONE, nullptr, },
  48. };
  49. /*
  50. 这里才是真正的定义,分配内存
  51. const:这个数组是常量,不能修改
  52. Parameters::Param:使用Parameters类内部定义的Param结构体类型
  53. Parameters::params:定义Parameters类的静态成员变量params
  54. []:这是一个数组
  55. */
  56. /*
  57. get count of parameters capable of being converted to load
  58. */
  59. uint16_t Parameters::param_count_float(void)
  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::INT8:
  69. case ParamType::UINT32:
  70. case ParamType::FLOAT:
  71. count++;
  72. break;
  73. }
  74. }
  75. // remove 1 for DONE_INIT
  76. return count-1;
  77. }
  78. /*
  79. 仅获取那些能够表示为浮点数的参数的索引
  80. */
  81. int16_t Parameters::param_index_float(const Parameters::Param *f)
  82. {
  83. uint16_t count = 0;
  84. for (const auto &p : params) {
  85. if (p.flags & PARAM_FLAG_HIDDEN) {
  86. continue;
  87. }
  88. switch (p.ptype) {
  89. case ParamType::UINT8:
  90. case ParamType::INT8:
  91. case ParamType::UINT32:
  92. case ParamType::FLOAT:
  93. if (&p == f) {
  94. return count;
  95. }
  96. count++;
  97. break;
  98. }
  99. }
  100. return -1;
  101. }
  102. /*
  103. find by name
  104. */
  105. const Parameters::Param *Parameters::find(const char *name)
  106. {
  107. for (const auto &p : params) {
  108. if (strcmp(name, p.name) == 0) {
  109. return &p;
  110. }
  111. }
  112. return nullptr;
  113. }
  114. /*
  115. find by index
  116. */
  117. const Parameters::Param *Parameters::find_by_index(uint16_t index)
  118. {
  119. if (index >= ARRAY_SIZE(params)-2) {
  120. return nullptr;
  121. }
  122. return &params[index];
  123. }
  124. /*
  125. find by index
  126. */
  127. const Parameters::Param *Parameters::find_by_index_float(uint16_t index)
  128. {
  129. uint16_t count = 0;
  130. for (const auto &p : params) {
  131. if (p.flags & PARAM_FLAG_HIDDEN) {
  132. continue;
  133. }
  134. switch (p.ptype) {
  135. case ParamType::UINT8:
  136. case ParamType::INT8:
  137. case ParamType::UINT32:
  138. case ParamType::FLOAT:
  139. if (index == count) {
  140. return &p;
  141. }
  142. count++;
  143. break;
  144. }
  145. }
  146. return nullptr;
  147. }
  148. void Parameters::Param::set_uint8(uint8_t v) const
  149. {
  150. auto *p = (uint8_t *)ptr;
  151. *p = v;
  152. nvs_set_u8(handle, name, *p);
  153. if (strcmp(name, "TO_DEFAULTS") == 0) {
  154. if (v == 1) {
  155. nvs_flash_erase();
  156. esp_restart();
  157. }
  158. }
  159. }
  160. void Parameters::Param::set_int8(int8_t v) const
  161. {
  162. auto *p = (int8_t *)ptr;
  163. *p = v;
  164. nvs_set_i8(handle, name, *p);
  165. }
  166. void Parameters::Param::set_uint32(uint32_t v) const
  167. {
  168. auto *p = (uint32_t *)ptr;
  169. *p = v;
  170. nvs_set_u32(handle, name, *p);
  171. }
  172. void Parameters::Param::set_float(float v) const
  173. {
  174. auto *p = (float *)ptr;
  175. *p = v;
  176. union {
  177. float f;
  178. uint32_t u32;
  179. } u;
  180. u.f = v;
  181. nvs_set_u32(handle, name, u.u32);
  182. }
  183. void Parameters::Param::set_char20(const char *v) const
  184. {
  185. if (min_len > 0 && strlen(v) < min_len) {
  186. return;
  187. }
  188. memset((void*)ptr, 0, 21);
  189. strncpy((char *)ptr, v, 20);
  190. nvs_set_str(handle, name, v);
  191. }
  192. void Parameters::Param::set_char64(const char *v) const
  193. {
  194. if (min_len > 0 && strlen(v) < min_len) {
  195. return;
  196. }
  197. memset((void*)ptr, 0, 65);
  198. strncpy((char *)ptr, v, 64);
  199. nvs_set_str(handle, name, v);
  200. }
  201. uint8_t Parameters::Param::get_uint8() const
  202. {
  203. const auto *p = (const uint8_t *)ptr;
  204. return *p;
  205. }
  206. int8_t Parameters::Param::get_int8() const
  207. {
  208. const auto *p = (const int8_t *)ptr;
  209. return *p;
  210. }
  211. uint32_t Parameters::Param::get_uint32() const
  212. {
  213. const auto *p = (const uint32_t *)ptr;
  214. return *p;
  215. }
  216. float Parameters::Param::get_float() const
  217. {
  218. const auto *p = (const float *)ptr;
  219. return *p;
  220. }
  221. const char *Parameters::Param::get_char20() const
  222. {
  223. const char *p = (const char *)ptr;
  224. return p;
  225. }
  226. const char *Parameters::Param::get_char64() const
  227. {
  228. const char *p = (const char *)ptr;
  229. return p;
  230. }
  231. /*
  232. get parameter as a float
  233. */
  234. bool Parameters::Param::get_as_float(float &v) const
  235. {
  236. switch (ptype) {
  237. case ParamType::UINT8:
  238. v = float(get_uint8());
  239. break;
  240. case ParamType::INT8:
  241. v = float(get_int8());
  242. break;
  243. case ParamType::UINT32:
  244. v = float(get_uint32());
  245. break;
  246. case ParamType::FLOAT:
  247. v = get_float();
  248. break;
  249. default:
  250. return false;
  251. }
  252. return true;
  253. }
  254. /*
  255. set parameter from a float
  256. */
  257. void Parameters::Param::set_as_float(float v) const
  258. {
  259. switch (ptype) {
  260. case ParamType::UINT8:
  261. set_uint8(uint8_t(v));
  262. break;
  263. case ParamType::INT8:
  264. set_int8(int8_t(v));
  265. break;
  266. case ParamType::UINT32:
  267. set_uint32(uint32_t(v));
  268. break;
  269. case ParamType::FLOAT:
  270. set_float(v);
  271. break;
  272. }
  273. }
  274. /*
  275. load defaults from parameter table
  276. */
  277. void Parameters::load_defaults(void)
  278. {
  279. for (const auto &p : params) {
  280. switch (p.ptype) {
  281. case ParamType::UINT8:
  282. *(uint8_t *)p.ptr = uint8_t(p.default_value);
  283. break;
  284. case ParamType::INT8:
  285. *(int8_t *)p.ptr = int8_t(p.default_value);
  286. break;
  287. case ParamType::UINT32:
  288. *(uint32_t *)p.ptr = uint32_t(p.default_value);
  289. break;
  290. case ParamType::FLOAT:
  291. *(float *)p.ptr = p.default_value;
  292. break;
  293. }
  294. }
  295. }
  296. void Parameters::init(void)
  297. {
  298. load_defaults(); // 遍历 params 数组,将每个参数的 “默认值” 写入对应的全局变量
  299. // 初始化 NVS 并读取保存的参数
  300. if (nvs_flash_init() != ESP_OK ||
  301. nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
  302. Serial.printf("NVS init failed\n");
  303. }
  304. // load values from NVS
  305. for (const auto &p : params) {
  306. switch (p.ptype) {
  307. case ParamType::UINT8:
  308. nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
  309. break;
  310. case ParamType::INT8:
  311. nvs_get_i8(handle, p.name, (int8_t *)p.ptr);
  312. break;
  313. case ParamType::UINT32:
  314. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  315. break;
  316. case ParamType::FLOAT:
  317. nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
  318. break;
  319. case ParamType::CHAR20: {
  320. size_t len = 21;
  321. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  322. break;
  323. }
  324. case ParamType::CHAR64: {
  325. size_t len = 65;
  326. nvs_get_str(handle, p.name, (char *)p.ptr, &len);
  327. break;
  328. }
  329. }
  330. }
  331. // 补全 WiFi SSID(无配置时自动生成)
  332. if (strlen(g.wifi_ssid) == 0) {
  333. uint8_t mac[6] {};
  334. esp_read_mac(mac, ESP_MAC_WIFI_STA);
  335. snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
  336. mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
  337. }
  338. if (g.to_factory_defaults == 1) { // 处理恢复出厂设置(应急重置)
  339. //should not happen, but in case the parameter is still set to 1, erase flash and reboot
  340. nvs_flash_erase();
  341. esp_restart();
  342. }
  343. // 首次初始化(仅上电第一次执行)
  344. if (g.done_init == 0) {
  345. set_by_name_uint8("DONE_INIT", 1);
  346. // setup public keys
  347. set_by_name_char64("PUBLIC_KEY1", ROMFS::find_string("public_keys/VKRID_public_key.dat"));
  348. // set_by_name_char64("PUBLIC_KEY2", ROMFS::find_string("public_keys/ArduPilot_public_key2.dat"));
  349. // #if defined(BOARD_BLUEMARK_DB200) || defined(BOARD_BLUEMARK_DB110) || defined(BOARD_BLUEMARK_DB202) || defined(BOARD_BLUEMARK_DB210) || defined(BOARD_BLUEMARK_DB203)
  350. // set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/BlueMark_public_key1.dat"));
  351. // #elif defined(BOARD_CUAV_RID)
  352. // set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/CUAV_public_key1.dat"));
  353. // #else
  354. // set_by_name_char64("PUBLIC_KEY3", ROMFS::find_string("public_keys/ArduPilot_public_key3.dat"));
  355. // #endif
  356. }
  357. }
  358. /*
  359. check if BasicID info is filled in with parameters
  360. */
  361. bool Parameters::have_basic_id_info(void) const
  362. {
  363. return strlen(g.uas_id) > 0 && g.id_type > 0 && g.ua_type > 0;
  364. }
  365. bool Parameters::have_basic_id_2_info(void) const
  366. {
  367. return strlen(g.uas_id_2) > 0 && g.id_type_2 > 0 && g.ua_type_2 > 0;
  368. }
  369. bool Parameters::set_by_name_uint8(const char *name, uint8_t v)
  370. {
  371. const auto *f = find(name);
  372. if (!f) {
  373. return false;
  374. }
  375. f->set_uint8(v);
  376. return true;
  377. }
  378. bool Parameters::set_by_name_int8(const char *name, int8_t v)
  379. {
  380. const auto *f = find(name);
  381. if (!f) {
  382. return false;
  383. }
  384. f->set_int8(v);
  385. return true;
  386. }
  387. bool Parameters::set_by_name_char64(const char *name, const char *s)
  388. {
  389. const auto *f = find(name);
  390. if (!f) {
  391. return false;
  392. }
  393. f->set_char64(s);
  394. return true;
  395. }
  396. bool Parameters::set_by_name_string(const char *name, const char *s)
  397. {
  398. const auto *f = find(name);
  399. if (!f) {
  400. return false;
  401. }
  402. switch (f->ptype) {
  403. case ParamType::UINT8:
  404. f->set_uint8(uint8_t(strtoul(s, nullptr, 0)));
  405. return true;
  406. case ParamType::INT8:
  407. f->set_int8(int8_t(strtoul(s, nullptr, 0)));
  408. return true;
  409. case ParamType::UINT32:
  410. f->set_uint32(strtoul(s, nullptr, 0));
  411. return true;
  412. case ParamType::FLOAT:
  413. f->set_float(atof(s));
  414. return true;
  415. case ParamType::CHAR20:
  416. f->set_char20(s);
  417. return true;
  418. case ParamType::CHAR64:
  419. f->set_char64(s);
  420. return true;
  421. }
  422. return false;
  423. }
  424. /*
  425. return a public key
  426. */
  427. bool Parameters::get_public_key(uint8_t i, uint8_t key[32]) const
  428. {
  429. if (i >= MAX_PUBLIC_KEYS) {
  430. return false;
  431. }
  432. const char *b64_key = g.public_keys[i].b64_key;
  433. const char *ktype = "PUBLIC_KEYV1:";
  434. if (strncmp(b64_key, ktype, strlen(ktype)) != 0) {
  435. return false;
  436. }
  437. b64_key += strlen(ktype);
  438. int32_t out_len = base64_decode(b64_key, key, 32);
  439. if (out_len != 32) {
  440. return false;
  441. }
  442. return true;
  443. }
  444. bool Parameters::no_public_keys(void) const
  445. {
  446. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  447. uint8_t key[32];
  448. if (get_public_key(i, key)) {
  449. return false;
  450. }
  451. }
  452. return true;
  453. }
  454. bool Parameters::set_public_key(uint8_t i, const uint8_t key[32])
  455. {
  456. if (i >= MAX_PUBLIC_KEYS) {
  457. return false;
  458. }
  459. char *s = base64_encode(key, PUBLIC_KEY_LEN);
  460. if (s == nullptr) {
  461. return false;
  462. }
  463. char name[] = "PUBLIC_KEYx";
  464. name[strlen(name)-2] = '1'+i;
  465. bool ret = set_by_name_char64(name, s);
  466. delete[] s;
  467. return ret;
  468. }
  469. bool Parameters::remove_public_key(uint8_t i)
  470. {
  471. if (i >= MAX_PUBLIC_KEYS) {
  472. return false;
  473. }
  474. char name[] = "PUBLIC_KEYx";
  475. name[strlen(name)-2] = '1'+i;
  476. return set_by_name_char64(name, "");
  477. }