GCS_MAVLink.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /// @file GCS_MAVLink.cpp
  14. /*
  15. This provides some support code and variables for MAVLink enabled sketches
  16. */
  17. #include "GCS.h"
  18. #include "GCS_MAVLink.h"
  19. #include <AP_Common/AP_Common.h>
  20. #include <AP_GPS/AP_GPS.h>
  21. #include <AP_HAL/AP_HAL.h>
  22. extern const AP_HAL::HAL& hal;
  23. #ifdef MAVLINK_SEPARATE_HELPERS
  24. // Shut up warnings about missing declarations; TODO: should be fixed on
  25. // mavlink/pymavlink project for when MAVLINK_SEPARATE_HELPERS is defined
  26. #pragma GCC diagnostic push
  27. #pragma GCC diagnostic ignored "-Wmissing-declarations"
  28. #include "include/mavlink/v2.0/mavlink_helpers.h"
  29. #pragma GCC diagnostic pop
  30. #endif
  31. AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
  32. bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS];
  33. // per-channel lock
  34. static HAL_Semaphore chan_locks[MAVLINK_COMM_NUM_BUFFERS];
  35. mavlink_system_t mavlink_system = {7,1};
  36. // mask of serial ports disabled to allow for SERIAL_CONTROL
  37. static uint8_t mavlink_locked_mask;
  38. // routing table
  39. MAVLink_routing GCS_MAVLINK::routing;
  40. /*
  41. lock a channel, preventing use by MAVLink
  42. */
  43. void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
  44. {
  45. if (!valid_channel(chan)) {
  46. return;
  47. }
  48. if (lock) {
  49. mavlink_locked_mask |= (1U<<(unsigned)_chan);
  50. } else {
  51. mavlink_locked_mask &= ~(1U<<(unsigned)_chan);
  52. }
  53. }
  54. bool GCS_MAVLINK::locked() const
  55. {
  56. return (1U<<chan) & mavlink_locked_mask;
  57. }
  58. // set a channel as private. Private channels get sent heartbeats, but
  59. // don't get broadcast packets or forwarded packets
  60. void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
  61. {
  62. const uint8_t mask = (1U<<(unsigned)_chan);
  63. mavlink_private |= mask;
  64. mavlink_active &= ~mask;
  65. }
  66. // return a MAVLink parameter type given a AP_Param type
  67. MAV_PARAM_TYPE GCS_MAVLINK::mav_param_type(enum ap_var_type t)
  68. {
  69. if (t == AP_PARAM_INT8) {
  70. return MAV_PARAM_TYPE_INT8;
  71. }
  72. if (t == AP_PARAM_INT16) {
  73. return MAV_PARAM_TYPE_INT16;
  74. }
  75. if (t == AP_PARAM_INT32) {
  76. return MAV_PARAM_TYPE_INT32;
  77. }
  78. // treat any others as float
  79. return MAV_PARAM_TYPE_REAL32;
  80. }
  81. /// Check for available transmit space on the nominated MAVLink channel
  82. ///
  83. /// @param chan Channel to check
  84. /// @returns Number of bytes available
  85. uint16_t comm_get_txspace(mavlink_channel_t chan)
  86. {
  87. if (!valid_channel(chan)) {
  88. return 0;
  89. }
  90. if ((1U<<chan) & mavlink_locked_mask) {
  91. return 0;
  92. }
  93. int16_t ret = mavlink_comm_port[chan]->txspace();
  94. if (ret < 0) {
  95. ret = 0;
  96. }
  97. return (uint16_t)ret;
  98. }
  99. /*
  100. send a buffer out a MAVLink channel
  101. */
  102. void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
  103. {
  104. if (!valid_channel(chan)) {
  105. return;
  106. }
  107. if (gcs_alternative_active[chan]) {
  108. // an alternative protocol is active
  109. return;
  110. }
  111. const size_t written = mavlink_comm_port[chan]->write(buf, len);
  112. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  113. if (written < len) {
  114. AP_HAL::panic("Short write on UART: %lu < %u", written, len);
  115. }
  116. #else
  117. (void)written;
  118. #endif
  119. }
  120. /*
  121. lock a channel for send
  122. */
  123. void comm_send_lock(mavlink_channel_t chan)
  124. {
  125. chan_locks[(uint8_t)chan].take_blocking();
  126. }
  127. /*
  128. unlock a channel
  129. */
  130. void comm_send_unlock(mavlink_channel_t chan)
  131. {
  132. chan_locks[(uint8_t)chan].give();
  133. }