parameters.cpp 15 KB

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