transport.cpp 4.0 KB

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