transport.cpp 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157
  1. /*
  2. generic transport class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include "transport.h"
  6. #include "parameters.h"
  7. #include "util.h"
  8. #include "monocypher.h"
  9. const char *Transport::parse_fail = "uninitialised";
  10. uint32_t Transport::last_location_ms;
  11. uint32_t Transport::last_basic_id_ms;
  12. uint32_t Transport::last_self_id_ms;
  13. uint32_t Transport::last_operator_id_ms;
  14. uint32_t Transport::last_system_ms;
  15. uint32_t Transport::last_system_timestamp;
  16. float Transport::last_location_timestamp;
  17. mavlink_open_drone_id_location_t Transport::location;
  18. mavlink_open_drone_id_basic_id_t Transport::basic_id;
  19. mavlink_open_drone_id_authentication_t Transport::authentication;
  20. mavlink_open_drone_id_self_id_t Transport::self_id;
  21. mavlink_open_drone_id_system_t Transport::system;
  22. mavlink_open_drone_id_operator_id_t Transport::operator_id;
  23. Transport::Transport()
  24. {
  25. }
  26. /*
  27. check we are OK to arm
  28. */
  29. uint8_t Transport::arm_status_check(const char *&reason)
  30. {
  31. const uint32_t max_age_location_ms = 3000;
  32. const uint32_t max_age_other_ms = 22000;
  33. const uint32_t now_ms = millis();
  34. uint8_t status = MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
  35. //return status OK if we have enabled the force arm option
  36. if (g.options & OPTIONS_FORCE_ARM_OK) {
  37. status = MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
  38. return status;
  39. }
  40. String ret = "";
  41. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  42. ret += "LOC ";
  43. }
  44. if (!g.have_basic_id_info()) {
  45. // if there is no basic ID data stored in the parameters give warning. If basic ID data are streamed to RID device,
  46. // it will store them in the parameters
  47. ret += "ID ";
  48. }
  49. if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  50. ret += "SELF_ID ";
  51. }
  52. if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  53. ret += "OP_ID ";
  54. }
  55. if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
  56. // we use location age limit for system as the operator location needs to come in as fast
  57. // as the vehicle location for FAA standard
  58. ret += "SYS ";
  59. }
  60. if (location.latitude == 0 && location.longitude == 0) { // 飞机经纬度数值是否符合范围
  61. ret += "LOC ";
  62. }
  63. if (system.operator_latitude == 0 && system.operator_longitude == 0) { // 操作员所在经纬度
  64. ret += "OP_LOC ";
  65. }
  66. if (ret.length() == 0 && reason == nullptr) {
  67. status = MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
  68. } else {
  69. static char return_string[200];
  70. memset(return_string, 0, sizeof(return_string));
  71. if (reason != nullptr) {
  72. strlcpy(return_string, reason, sizeof(return_string));
  73. }
  74. strlcat(return_string, ret.c_str(), sizeof(return_string));
  75. reason = return_string;
  76. }
  77. return status;
  78. }
  79. /*
  80. make a session key 用随机数 时间戳 mac地址生成当前64bit会话密钥
  81. */
  82. void Transport::make_session_key(uint8_t key[8]) const
  83. {
  84. struct {
  85. uint32_t time_us;
  86. uint8_t mac[8];
  87. uint32_t rand;
  88. } data {};
  89. static_assert(sizeof(data) % 4 == 0, "data must be multiple of 4 bytes");
  90. esp_efuse_mac_get_default(data.mac);
  91. data.time_us = micros();
  92. data.rand = random(0xFFFFFFFF);
  93. const uint64_t c64 = crc_crc64((const uint32_t *)&data, sizeof(data)/sizeof(uint32_t));
  94. memcpy(key, (uint8_t *)&c64, 8);
  95. }
  96. /*
  97. 数字签名验证函数
  98. check signature in a command against public keys
  99. */
  100. bool Transport::check_signature(uint8_t sig_length, uint8_t data_len, uint32_t sequence, uint32_t operation,
  101. const uint8_t *data)
  102. {
  103. if (g.no_public_keys()) { // 通过不设置公钥跳过这个
  104. // allow through if no keys are setup
  105. // 如果未设置密钥,则允许通过
  106. return true;
  107. }
  108. if (sig_length != 64) {
  109. // Monocypher签名为64字节
  110. return false;
  111. }
  112. /*
  113. 遍历所有公钥,如果有一个匹配,那么我们就没问题了
  114. */
  115. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  116. uint8_t key[32];
  117. if (!g.get_public_key(i, key)) {
  118. continue;
  119. }
  120. crypto_check_ctx ctx {};
  121. crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx;
  122. crypto_check_init(actx, &data[data_len], key);
  123. crypto_check_update(actx, (const uint8_t*)&sequence, sizeof(sequence));
  124. crypto_check_update(actx, (const uint8_t*)&operation, sizeof(operation));
  125. crypto_check_update(actx, data, data_len);
  126. if (operation != SECURE_COMMAND_GET_SESSION_KEY &&
  127. operation != SECURE_COMMAND_GET_REMOTEID_SESSION_KEY) {
  128. crypto_check_update(actx, session_key, sizeof(session_key));
  129. }
  130. if (crypto_check_final(actx) == 0) {
  131. // good signature
  132. return true;
  133. }
  134. }
  135. return false;
  136. }