transport.cpp 2.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  1. /*
  2. generic transport class for handling OpenDroneID messages
  3. */
  4. #include <Arduino.h>
  5. #include "transport.h"
  6. const char *Transport::parse_fail = "uninitialised";
  7. uint32_t Transport::last_location_ms;
  8. uint32_t Transport::last_basic_id_ms;
  9. uint32_t Transport::last_self_id_ms;
  10. uint32_t Transport::last_operator_id_ms;
  11. uint32_t Transport::last_system_ms;
  12. mavlink_open_drone_id_location_t Transport::location;
  13. mavlink_open_drone_id_basic_id_t Transport::basic_id;
  14. mavlink_open_drone_id_authentication_t Transport::authentication;
  15. mavlink_open_drone_id_self_id_t Transport::self_id;
  16. mavlink_open_drone_id_system_t Transport::system;
  17. mavlink_open_drone_id_operator_id_t Transport::operator_id;
  18. Transport::Transport()
  19. {
  20. }
  21. /*
  22. check we are OK to arm
  23. */
  24. uint8_t Transport::arm_status_check(const char *&reason)
  25. {
  26. const uint32_t max_age_location_ms = 3000;
  27. const uint32_t max_age_other_ms = 22000;
  28. const uint32_t now_ms = millis();
  29. uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
  30. if (last_location_ms == 0 || now_ms - last_location_ms > max_age_location_ms) {
  31. reason = "missing location message";
  32. } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) {
  33. reason = "missing basic_id message";
  34. } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) {
  35. reason = "missing self_id message";
  36. } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) {
  37. reason = "missing operator_id message";
  38. } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_location_ms) {
  39. // we use location age limit for system as the operator location needs to come in as fast
  40. // as the vehicle location for FAA standard
  41. reason = "missing system message";
  42. } else if (location.latitude == 0 && location.longitude == 0) {
  43. reason = "Bad location";
  44. } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
  45. reason = "Bad operator location";
  46. } else if (reason == nullptr) {
  47. status = MAV_ODID_GOOD_TO_ARM;
  48. }
  49. return status;
  50. }