mavlink.h 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. /*
  2. mavlink class for handling OpenDroneID messages
  3. */
  4. #pragma once
  5. // we have separate helpers disabled to make it possible
  6. // to select MAVLink 1.0 in the arduino GUI build
  7. #define MAVLINK_SEPARATE_HELPERS
  8. #define MAVLINK_NO_CONVERSION_HELPERS
  9. #define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
  10. // two buffers, one for USB, one for UART. This makes for easier testing with SITL
  11. #define MAVLINK_COMM_NUM_BUFFERS 2
  12. #define MAVLINK_MAX_PAYLOAD_LEN 255
  13. #include <mavlink2.h>
  14. /// MAVLink system definition
  15. extern mavlink_system_t mavlink_system;
  16. void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
  17. #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
  18. #include <generated/all/mavlink.h>
  19. /*
  20. abstraction for MAVLink on a serial port
  21. */
  22. class MAVLinkSerial {
  23. public:
  24. MAVLinkSerial(HardwareSerial &serial, mavlink_channel_t chan);
  25. void init(void);
  26. void update(void);
  27. const mavlink_open_drone_id_location_t &get_location(void) const {
  28. return location;
  29. }
  30. const mavlink_open_drone_id_basic_id_t &get_basic_id(void) const {
  31. return basic_id;
  32. }
  33. const mavlink_open_drone_id_authentication_t &get_authentication(void) const {
  34. return authentication;
  35. }
  36. const mavlink_open_drone_id_self_id_t &get_self_id(void) const {
  37. return self_id;
  38. }
  39. const mavlink_open_drone_id_system_t &get_system(void) const {
  40. return system;
  41. }
  42. const mavlink_open_drone_id_operator_id_t &get_operator_id(void) const {
  43. return operator_id;
  44. }
  45. uint32_t last_location_ms;
  46. uint32_t last_basic_id_ms;
  47. uint32_t last_self_id_ms;
  48. uint32_t last_operator_id_ms;
  49. uint32_t last_system_ms;
  50. uint32_t get_last_location_ms(void) {
  51. return last_location_ms;
  52. }
  53. void set_parse_fail(const char *msg) {
  54. parse_fail = msg;
  55. }
  56. private:
  57. HardwareSerial &serial;
  58. mavlink_channel_t chan;
  59. uint32_t last_hb_ms;
  60. void update_receive(void);
  61. void update_send(void);
  62. void process_packet(mavlink_status_t &status, mavlink_message_t &msg);
  63. void mav_printf(uint8_t severity, const char *fmt, ...);
  64. void arm_status_send(void);
  65. mavlink_open_drone_id_location_t location;
  66. mavlink_open_drone_id_basic_id_t basic_id;
  67. mavlink_open_drone_id_authentication_t authentication;
  68. mavlink_open_drone_id_self_id_t self_id;
  69. mavlink_open_drone_id_system_t system;
  70. mavlink_open_drone_id_operator_id_t operator_id;
  71. const char *parse_fail;
  72. };