transport.cpp 2.1 KB

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