mavlink_secure_command.cpp 3.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116
  1. /*
  2. mavlink class for handling SECURE_COMMAND messages
  3. */
  4. #include <Arduino.h>
  5. #include "mavlink.h"
  6. #include "board_config.h"
  7. #include "version.h"
  8. #include "parameters.h"
  9. /*
  10. handle a SECURE_COMMAND
  11. */
  12. void MAVLinkSerial::handle_secure_command(const mavlink_secure_command_t &pkt)
  13. {
  14. mavlink_secure_command_reply_t reply {};
  15. reply.result = MAV_RESULT_UNSUPPORTED;
  16. reply.sequence = pkt.sequence;
  17. reply.operation = pkt.operation;
  18. if (uint16_t(pkt.data_length) + uint16_t(pkt.sig_length) > sizeof(pkt.data)) {
  19. reply.result = MAV_RESULT_DENIED;
  20. goto send_reply;
  21. }
  22. if (!check_signature(pkt.sig_length, pkt.data_length, pkt.sequence, pkt.operation, pkt.data)) {
  23. reply.result = MAV_RESULT_DENIED;
  24. goto send_reply;
  25. }
  26. switch (pkt.operation) {
  27. case SECURE_COMMAND_GET_SESSION_KEY: {
  28. make_session_key(session_key);
  29. reply.data_length = sizeof(session_key);
  30. memcpy(reply.data, session_key, reply.data_length);
  31. reply.result = MAV_RESULT_ACCEPTED;
  32. break;
  33. }
  34. case SECURE_COMMAND_GET_PUBLIC_KEYS: {
  35. if (pkt.data_length != 2) {
  36. reply.result = MAV_RESULT_UNSUPPORTED;
  37. goto send_reply;
  38. }
  39. const uint8_t key_idx = pkt.data[0];
  40. uint8_t num_keys = pkt.data[1];
  41. const uint8_t max_fetch = (sizeof(reply.data)-1) / PUBLIC_KEY_LEN;
  42. if (key_idx >= MAX_PUBLIC_KEYS ||
  43. num_keys > max_fetch ||
  44. key_idx+num_keys > MAX_PUBLIC_KEYS ||
  45. g.no_public_keys()) {
  46. reply.result = MAV_RESULT_FAILED;
  47. goto send_reply;
  48. }
  49. for (uint8_t i=0;i<num_keys;i++) {
  50. g.get_public_key(i+key_idx, &reply.data[1+i*PUBLIC_KEY_LEN]);
  51. }
  52. reply.data_length = 1+num_keys*PUBLIC_KEY_LEN;
  53. reply.data[0] = key_idx;
  54. reply.result = MAV_RESULT_ACCEPTED;
  55. break;
  56. }
  57. case SECURE_COMMAND_SET_PUBLIC_KEYS: {
  58. if (pkt.data_length < PUBLIC_KEY_LEN+1) {
  59. reply.result = MAV_RESULT_FAILED;
  60. goto send_reply;
  61. }
  62. const uint8_t key_idx = pkt.data[0];
  63. const uint8_t num_keys = (pkt.data_length-1) / PUBLIC_KEY_LEN;
  64. if (num_keys == 0) {
  65. reply.result = MAV_RESULT_FAILED;
  66. goto send_reply;
  67. }
  68. if (key_idx >= MAX_PUBLIC_KEYS ||
  69. key_idx+num_keys > MAX_PUBLIC_KEYS) {
  70. reply.result = MAV_RESULT_FAILED;
  71. goto send_reply;
  72. }
  73. bool failed = false;
  74. for (uint8_t i=0; i<num_keys; i++) {
  75. failed |= !g.set_public_key(key_idx+i, &pkt.data[1+i*PUBLIC_KEY_LEN]);
  76. }
  77. reply.result = failed? MAV_RESULT_FAILED : MAV_RESULT_ACCEPTED;
  78. break;
  79. }
  80. case SECURE_COMMAND_REMOVE_PUBLIC_KEYS: {
  81. if (pkt.data_length != 2) {
  82. reply.result = MAV_RESULT_FAILED;
  83. goto send_reply;
  84. }
  85. const uint8_t key_idx = pkt.data[0];
  86. const uint8_t num_keys = pkt.data[1];
  87. if (num_keys == 0) {
  88. reply.result = MAV_RESULT_FAILED;
  89. goto send_reply;
  90. }
  91. if (key_idx >= MAX_PUBLIC_KEYS ||
  92. key_idx+num_keys > MAX_PUBLIC_KEYS) {
  93. reply.result = MAV_RESULT_FAILED;
  94. goto send_reply;
  95. }
  96. for (uint8_t i=0; i<num_keys; i++) {
  97. g.remove_public_key(key_idx+i);
  98. }
  99. reply.result = MAV_RESULT_ACCEPTED;
  100. break;
  101. }
  102. }
  103. send_reply:
  104. // send reply
  105. mavlink_msg_secure_command_reply_send_struct(chan, &reply);
  106. }