GCS_Signing.cpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267
  1. /*
  2. Code for handling MAVLink2 signing
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. #include "GCS.h"
  15. extern const AP_HAL::HAL& hal;
  16. // storage object
  17. StorageAccess GCS_MAVLINK::_signing_storage(StorageManager::StorageKeys);
  18. // magic for versioning of the structure
  19. #define SIGNING_KEY_MAGIC 0x3852fcd1
  20. // structure stored in FRAM
  21. struct SigningKey {
  22. uint32_t magic;
  23. uint64_t timestamp;
  24. uint8_t secret_key[32];
  25. };
  26. // shared signing_streams structure
  27. mavlink_signing_streams_t GCS_MAVLINK::signing_streams;
  28. // last time we saved the timestamp
  29. uint32_t GCS_MAVLINK::last_signing_save_ms;
  30. bool GCS_MAVLINK::signing_key_save(const struct SigningKey &key)
  31. {
  32. if (_signing_storage.size() < sizeof(key)) {
  33. return false;
  34. }
  35. return _signing_storage.write_block(0, &key, sizeof(key));
  36. }
  37. bool GCS_MAVLINK::signing_key_load(struct SigningKey &key)
  38. {
  39. if (_signing_storage.size() < sizeof(key)) {
  40. return false;
  41. }
  42. if (!_signing_storage.read_block(&key, 0, sizeof(key))) {
  43. return false;
  44. }
  45. if (key.magic != SIGNING_KEY_MAGIC) {
  46. return false;
  47. }
  48. return true;
  49. }
  50. /*
  51. handle a setup_signing message
  52. */
  53. void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg)
  54. {
  55. // setting up signing key when armed generally not useful /
  56. // possibly not a good idea
  57. if (hal.util->get_soft_armed()) {
  58. send_text(MAV_SEVERITY_WARNING, "ERROR: Won't setup signing when armed");
  59. return;
  60. }
  61. // decode
  62. mavlink_setup_signing_t packet;
  63. mavlink_msg_setup_signing_decode(&msg, &packet);
  64. struct SigningKey key;
  65. key.magic = SIGNING_KEY_MAGIC;
  66. key.timestamp = packet.initial_timestamp;
  67. memcpy(key.secret_key, packet.secret_key, 32);
  68. if (!signing_key_save(key)) {
  69. send_text(MAV_SEVERITY_WARNING, "ERROR: Failed to save signing key");
  70. return;
  71. }
  72. // activate it immediately
  73. load_signing_key();
  74. }
  75. /*
  76. callback to accept unsigned (or incorrectly signed) packets
  77. */
  78. extern "C" {
  79. static const uint32_t accept_list[] = {
  80. MAVLINK_MSG_ID_RADIO_STATUS,
  81. MAVLINK_MSG_ID_RADIO
  82. };
  83. static bool accept_unsigned_callback(const mavlink_status_t *status, uint32_t msgId)
  84. {
  85. if (status == mavlink_get_channel_status(MAVLINK_COMM_0)) {
  86. // always accept channel 0, assumed to be secure channel. This
  87. // is USB on PX4 boards
  88. return true;
  89. }
  90. for (uint8_t i=0; i<ARRAY_SIZE(accept_list); i++) {
  91. if (accept_list[i] == msgId) {
  92. return true;
  93. }
  94. }
  95. return false;
  96. }
  97. }
  98. /*
  99. load signing key
  100. */
  101. void GCS_MAVLINK::load_signing_key(void)
  102. {
  103. struct SigningKey key;
  104. if (!signing_key_load(key)) {
  105. return;
  106. }
  107. mavlink_status_t *status = mavlink_get_channel_status(chan);
  108. if (status == nullptr) {
  109. hal.console->printf("Failed to load signing key - no status");
  110. return;
  111. }
  112. memcpy(signing.secret_key, key.secret_key, 32);
  113. signing.link_id = (uint8_t)chan;
  114. // use a timestamp 1 minute past the last recorded
  115. // timestamp. Combined with saving the key once every 30s this
  116. // prevents a window for replay attacks
  117. signing.timestamp = key.timestamp + 60UL * 100UL * 1000UL;
  118. signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
  119. signing.accept_unsigned_callback = accept_unsigned_callback;
  120. // if timestamp and key are all zero then we disable signing
  121. bool all_zero = (key.timestamp == 0);
  122. for (uint8_t i=0; i<sizeof(key.secret_key); i++) {
  123. if (signing.secret_key[i] != 0) {
  124. all_zero = false;
  125. break;
  126. }
  127. }
  128. // enable signing on all channels
  129. for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
  130. mavlink_status_t *cstatus = mavlink_get_channel_status((mavlink_channel_t)(MAVLINK_COMM_0 + i));
  131. if (cstatus != nullptr) {
  132. if (all_zero) {
  133. // disable signing
  134. cstatus->signing = nullptr;
  135. cstatus->signing_streams = nullptr;
  136. } else {
  137. cstatus->signing = &signing;
  138. cstatus->signing_streams = &signing_streams;
  139. }
  140. }
  141. }
  142. }
  143. /*
  144. update signing timestamp. This is called when we get GPS lock
  145. timestamp_usec is since 1/1/1970 (the epoch)
  146. */
  147. void GCS_MAVLINK::update_signing_timestamp(uint64_t timestamp_usec)
  148. {
  149. uint64_t signing_timestamp = (timestamp_usec / (1000*1000ULL));
  150. // this is the offset from 1/1/1970 to 1/1/2015
  151. const uint64_t epoch_offset = 1420070400;
  152. if (signing_timestamp > epoch_offset) {
  153. signing_timestamp -= epoch_offset;
  154. }
  155. // convert to 10usec units
  156. signing_timestamp *= 100 * 1000ULL;
  157. // increase signing timestamp on any links that have signing
  158. for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
  159. mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
  160. mavlink_status_t *status = mavlink_get_channel_status(chan);
  161. if (status && status->signing && status->signing->timestamp < signing_timestamp) {
  162. status->signing->timestamp = signing_timestamp;
  163. }
  164. }
  165. // save to stable storage
  166. save_signing_timestamp(true);
  167. }
  168. /*
  169. save the signing timestamp periodically
  170. */
  171. void GCS_MAVLINK::save_signing_timestamp(bool force_save_now)
  172. {
  173. uint32_t now = AP_HAL::millis();
  174. // we save the timestamp every 30s, unless forced by a GPS update
  175. if (!force_save_now && now - last_signing_save_ms < 30*1000UL) {
  176. return;
  177. }
  178. last_signing_save_ms = now;
  179. struct SigningKey key;
  180. if (!signing_key_load(key)) {
  181. return;
  182. }
  183. bool need_save = false;
  184. for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
  185. mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
  186. const mavlink_status_t *status = mavlink_get_channel_status(chan);
  187. if (status && status->signing && status->signing->timestamp > key.timestamp) {
  188. key.timestamp = status->signing->timestamp;
  189. need_save = true;
  190. }
  191. }
  192. if (need_save) {
  193. // save updated key
  194. signing_key_save(key);
  195. }
  196. }
  197. /*
  198. return true if signing is enabled on this channel
  199. */
  200. bool GCS_MAVLINK::signing_enabled(void) const
  201. {
  202. const mavlink_status_t *status = mavlink_get_channel_status(chan);
  203. if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
  204. return true;
  205. }
  206. return false;
  207. }
  208. /*
  209. return packet overhead in bytes for a channel
  210. */
  211. uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan)
  212. {
  213. /*
  214. reserve 100 bytes for parameters when a GCS fails to fetch a
  215. parameter due to lack of buffer space. The reservation lasts 2
  216. seconds
  217. */
  218. uint8_t reserved_space = 0;
  219. if (reserve_param_space_start_ms != 0 &&
  220. AP_HAL::millis() - reserve_param_space_start_ms < 2000) {
  221. reserved_space = 100;
  222. } else {
  223. reserve_param_space_start_ms = 0;
  224. }
  225. const mavlink_status_t *status = mavlink_get_channel_status(chan);
  226. if (status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) {
  227. return MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN + reserved_space;
  228. }
  229. return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space;
  230. }