transport.cpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  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_PRE_ARM_FAIL_GENERIC;
  35. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  36. reason = "missing location message";
  37. } else if (!g.have_basic_id_info() && (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms)) {
  38. reason = "missing basic_id message";
  39. } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  40. reason = "missing self_id message";
  41. } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  42. reason = "missing operator_id message";
  43. } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
  44. // we use location age limit for system as the operator location needs to come in as fast
  45. // as the vehicle location for FAA standard
  46. reason = "missing system message";
  47. } else if (location.latitude == 0 && location.longitude == 0) {
  48. reason = "Bad location";
  49. } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
  50. reason = "Bad operator location";
  51. } else if (reason == nullptr) {
  52. status = MAV_ODID_GOOD_TO_ARM;
  53. }
  54. return status;
  55. }
  56. /*
  57. make a session key
  58. */
  59. void Transport::make_session_key(uint8_t key[8]) const
  60. {
  61. struct {
  62. uint32_t time_us;
  63. uint8_t mac[8];
  64. uint32_t rand;
  65. } data {};
  66. static_assert(sizeof(data) % 4 == 0, "data must be multiple of 4 bytes");
  67. esp_efuse_mac_get_default(data.mac);
  68. data.time_us = micros();
  69. data.rand = random(0xFFFFFFFF);
  70. const uint64_t c64 = crc_crc64((const uint32_t *)&data, sizeof(data)/sizeof(uint32_t));
  71. memcpy(key, (uint8_t *)&c64, 8);
  72. }
  73. /*
  74. check signature in a command against public keys
  75. */
  76. bool Transport::check_signature(uint8_t sig_length, uint8_t data_len, uint32_t sequence, uint32_t operation,
  77. const uint8_t *data)
  78. {
  79. if (g.no_public_keys()) {
  80. // allow through if no keys are setup
  81. return true;
  82. }
  83. if (sig_length != 64) {
  84. // monocypher signatures are 64 bytes
  85. return false;
  86. }
  87. /*
  88. loop over all public keys, if one matches then we are OK
  89. */
  90. for (uint8_t i=0; i<MAX_PUBLIC_KEYS; i++) {
  91. uint8_t key[32];
  92. if (!g.get_public_key(i, key)) {
  93. continue;
  94. }
  95. crypto_check_ctx ctx {};
  96. crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx;
  97. crypto_check_init(actx, &data[data_len], key);
  98. crypto_check_update(actx, (const uint8_t*)&sequence, sizeof(sequence));
  99. crypto_check_update(actx, (const uint8_t*)&operation, sizeof(operation));
  100. crypto_check_update(actx, data, data_len);
  101. if (operation != SECURE_COMMAND_GET_SESSION_KEY &&
  102. operation != SECURE_COMMAND_GET_REMOTEID_SESSION_KEY) {
  103. crypto_check_update(actx, session_key, sizeof(session_key));
  104. }
  105. if (crypto_check_final(actx) == 0) {
  106. // good signature
  107. return true;
  108. }
  109. }
  110. return false;
  111. }