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