GCS_serial_control.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. /*
  2. MAVLink SERIAL_CONTROL handling
  3. */
  4. /*
  5. This program is free software: you can redistribute it and/or modify
  6. it under the terms of the GNU General Public License as published by
  7. the Free Software Foundation, either version 3 of the License, or
  8. (at your option) any later version.
  9. This program is distributed in the hope that it will be useful,
  10. but WITHOUT ANY WARRANTY; without even the implied warranty of
  11. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  12. GNU General Public License for more details.
  13. You should have received a copy of the GNU General Public License
  14. along with this program. If not, see <http://www.gnu.org/licenses/>.
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "GCS.h"
  18. #include <AP_Logger/AP_Logger.h>
  19. #include <AP_GPS/AP_GPS.h>
  20. extern const AP_HAL::HAL& hal;
  21. /**
  22. handle a SERIAL_CONTROL message
  23. */
  24. void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg)
  25. {
  26. mavlink_serial_control_t packet;
  27. mavlink_msg_serial_control_decode(&msg, &packet);
  28. AP_HAL::UARTDriver *port = nullptr;
  29. AP_HAL::BetterStream *stream = nullptr;
  30. if (packet.flags & SERIAL_CONTROL_FLAG_REPLY) {
  31. // how did this packet get to us?
  32. return;
  33. }
  34. bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
  35. switch (packet.device) {
  36. case SERIAL_CONTROL_DEV_TELEM1:
  37. stream = port = hal.uartC;
  38. lock_channel(MAVLINK_COMM_1, exclusive);
  39. break;
  40. case SERIAL_CONTROL_DEV_TELEM2:
  41. stream = port = hal.uartD;
  42. lock_channel(MAVLINK_COMM_2, exclusive);
  43. break;
  44. case SERIAL_CONTROL_DEV_GPS1:
  45. stream = port = hal.uartB;
  46. AP::gps().lock_port(0, exclusive);
  47. break;
  48. case SERIAL_CONTROL_DEV_GPS2:
  49. stream = port = hal.uartE;
  50. AP::gps().lock_port(1, exclusive);
  51. break;
  52. case SERIAL_CONTROL_DEV_SHELL:
  53. stream = hal.util->get_shell_stream();
  54. if (stream == nullptr) {
  55. return;
  56. }
  57. break;
  58. default:
  59. // not supported yet
  60. return;
  61. }
  62. if (stream == nullptr) {
  63. // this is probably very bad
  64. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  65. AP_HAL::panic("stream is nullptr");
  66. #endif
  67. return;
  68. }
  69. if (exclusive && port != nullptr) {
  70. // force flow control off for exclusive access. This protocol
  71. // is used to talk to bootloaders which may not have flow
  72. // control support
  73. port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  74. }
  75. // optionally change the baudrate
  76. if (packet.baudrate != 0 && port != nullptr) {
  77. port->begin(packet.baudrate);
  78. }
  79. // write the data
  80. if (packet.count != 0) {
  81. if ((packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
  82. stream->write(packet.data, packet.count);
  83. } else {
  84. const uint8_t *data = &packet.data[0];
  85. uint8_t count = packet.count;
  86. while (count > 0) {
  87. while (stream->txspace() <= 0) {
  88. hal.scheduler->delay(5);
  89. }
  90. uint16_t n = stream->txspace();
  91. if (n > packet.count) {
  92. n = packet.count;
  93. }
  94. stream->write(data, n);
  95. data += n;
  96. count -= n;
  97. }
  98. }
  99. }
  100. if ((packet.flags & SERIAL_CONTROL_FLAG_RESPOND) == 0) {
  101. // no response expected
  102. return;
  103. }
  104. uint8_t flags = packet.flags;
  105. more_data:
  106. // sleep for the timeout
  107. while (packet.timeout != 0 &&
  108. stream->available() < (int16_t)sizeof(packet.data)) {
  109. hal.scheduler->delay(1);
  110. packet.timeout--;
  111. }
  112. packet.flags = SERIAL_CONTROL_FLAG_REPLY;
  113. // work out how many bytes are available
  114. int16_t available = stream->available();
  115. if (available < 0) {
  116. available = 0;
  117. }
  118. if (available > (int16_t)sizeof(packet.data)) {
  119. available = sizeof(packet.data);
  120. }
  121. if (available == 0 && (flags & SERIAL_CONTROL_FLAG_BLOCKING) == 0) {
  122. return;
  123. }
  124. if (packet.flags & SERIAL_CONTROL_FLAG_BLOCKING) {
  125. while (!HAVE_PAYLOAD_SPACE(chan, SERIAL_CONTROL)) {
  126. hal.scheduler->delay(1);
  127. }
  128. } else {
  129. if (!HAVE_PAYLOAD_SPACE(chan, SERIAL_CONTROL)) {
  130. // no space for reply
  131. return;
  132. }
  133. }
  134. // read any reply data
  135. packet.count = 0;
  136. memset(packet.data, 0, sizeof(packet.data));
  137. while (available > 0) {
  138. packet.data[packet.count++] = (uint8_t)stream->read();
  139. available--;
  140. }
  141. // and send the reply
  142. _mav_finalize_message_chan_send(chan,
  143. MAVLINK_MSG_ID_SERIAL_CONTROL,
  144. (const char *)&packet,
  145. MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN,
  146. MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
  147. MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
  148. if ((flags & SERIAL_CONTROL_FLAG_MULTI) && packet.count != 0) {
  149. if (flags & SERIAL_CONTROL_FLAG_BLOCKING) {
  150. hal.scheduler->delay(1);
  151. }
  152. goto more_data;
  153. }
  154. }