QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkConsoleController.cc
Go to the documentation of this file.
2#include "MAVLinkProtocol.h"
5#include "QGCPalette.h"
6#include "Vehicle.h"
8
9#include <QtGui/QGuiApplication>
10#include <QtGui/QClipboard>
11
12QGC_LOGGING_CATEGORY(MAVLinkConsoleControllerLog, "AnalyzeView.MAVLinkConsoleController")
13
15 : QStringListModel(parent)
16 , _palette(new QGCPalette(this))
17{
18 qCDebug(MAVLinkConsoleControllerLog) << this;
19
20 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle);
21
22 _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
23}
24
26{
27 if (_vehicle) {
28 QByteArray msg;
29 _sendSerialData(msg, true);
30 }
31
32 qCDebug(MAVLinkConsoleControllerLog) << this;
33}
34
35void MAVLinkConsoleController::sendCommand(const QString &command)
36{
37 QString output = command;
38
39 // there might be multiple commands, add them separately to the history
40 const QStringList lines = output.split('\n');
41 for (const QString &line : lines) {
42 if (!line.isEmpty()) {
43 _history.append(line);
44 }
45 }
46
47 (void) output.append("\n");
48 _sendSerialData(qPrintable(output));
49 _cursorHomePos = -1;
50}
51
52QString MAVLinkConsoleController::handleClipboard(const QString &command_pre)
53{
54 QString clipboardData = command_pre + QGuiApplication::clipboard()->text();
55
56 const int lastLinePos = clipboardData.lastIndexOf('\n');
57 if (lastLinePos != -1) {
58 const QString commands = clipboardData.mid(0, lastLinePos);
59 sendCommand(commands);
60 clipboardData = clipboardData.mid(lastLinePos + 1);
61 }
62
63 return clipboardData;
64}
65
66void MAVLinkConsoleController::_setActiveVehicle(Vehicle *vehicle)
67{
68 for (QMetaObject::Connection &con : _connections) {
69 (void) disconnect(con);
70 }
71 _connections.clear();
72
73 _vehicle = vehicle;
74 if (_vehicle) {
75 _incomingBuffer.clear();
76 // Reset the model
77 setStringList(QStringList());
78 _cursorY = 0;
79 _cursorX = 0;
80 _cursorHomePos = -1;
81 _connections << connect(_vehicle, &Vehicle::mavlinkSerialControl, this, &MAVLinkConsoleController::_receiveData);
82 }
83}
84
85void MAVLinkConsoleController::_receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, const QByteArray &data)
86{
87 Q_UNUSED(flags); Q_UNUSED(timeout); Q_UNUSED(baudrate);
88
89 if (device != SERIAL_CONTROL_DEV_SHELL) {
90 return;
91 }
92
93 // Append incoming data and parse for ANSI codes
94 (void) _incomingBuffer.append(data);
95
96 while (!_incomingBuffer.isEmpty()) {
97 bool newline = false;
98
99 int idx = _incomingBuffer.indexOf('\n');
100 if (idx == -1) {
101 // Read the whole incoming buffer
102 idx = _incomingBuffer.size();
103 } else {
104 newline = true;
105 }
106
107 QByteArray fragment = _incomingBuffer.mid(0, idx);
108 if (!_processANSItext(fragment)) {
109 // ANSI processing failed, need more data
110 return;
111 }
112
113 _writeLine(_cursorY, fragment);
114 if (newline) {
115 _cursorY++;
116 _cursorX = 0;
117 // ensure line exists
118 const int rc = rowCount();
119 if (_cursorY >= rc) {
120 (void) insertRows(rc, 1 + _cursorY - rc);
121 }
122 }
123
124 (void) _incomingBuffer.remove(0, idx + (newline ? 1 : 0));
125 }
126}
127
128void MAVLinkConsoleController::_sendSerialData(const QByteArray &data, bool close)
129{
130 if (!_vehicle) {
131 qCWarning(MAVLinkConsoleControllerLog) << "Internal error";
132 return;
133 }
134
135 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
136 if (!sharedLink) {
137 return;
138 }
139
140 // Send maximum sized chunks until the complete buffer is transmitted
141 QByteArray output(data);
142 while (output.size()) {
143 QByteArray chunk(output.left(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN));
144 const int dataSize = chunk.size();
145
146 // Ensure the buffer is large enough, as the MAVLink parser expects MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN bytes
147 (void) chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(), '\0');
148
149 const uint8_t flags = close ? 0 : SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
150
152 (void) mavlink_msg_serial_control_pack_chan(
155 sharedLink->mavlinkChannel(),
156 &msg,
157 SERIAL_CONTROL_DEV_SHELL,
158 flags,
159 0,
160 0,
161 dataSize,
162 reinterpret_cast<uint8_t*>(chunk.data()),
163 _vehicle->id(),
164 _vehicle->defaultComponentId()
165 );
166
167 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
168 (void) output.remove(0, chunk.size());
169 }
170}
171
172bool MAVLinkConsoleController::_processANSItext(QByteArray &line)
173{
174 // Iterate over the incoming buffer to parse off known ANSI control codes
175 for (int i = 0; i < line.size(); i++) {
176 if (line[i] != '\x1B') {
177 continue;
178 }
179
180 // For ANSI codes we expect at least 3 incoming chars
181 if ((i >= (line.size() - 2)) || (line[i + 1] != '[')) {
182 // We can reasonably expect a control code was fragemented
183 // Stop parsing here and wait for it to come in
184 return false;
185 }
186
187 switch (line[i + 2]) {
188 case 'H':
189 if (_cursorHomePos == -1) {
190 // Assign new home position if home is unset
191 _cursorHomePos = _cursorY;
192 } else {
193 // Rewind write cursor position to home
194 _cursorY = _cursorHomePos;
195 _cursorX = 0;
196 }
197 break;
198 case 'K':
199 // Erase the current line to the end
200 if (_cursorY < rowCount()) {
201 const QModelIndex idx = index(_cursorY);
202 QString updated = data(idx, Qt::DisplayRole).toString();
203 const int eraseIdx = _cursorX + i;
204 if (eraseIdx < updated.length()) {
205 (void) setData(idx, updated.remove(eraseIdx, updated.length()));
206 }
207 }
208 break;
209 case '2':
210 // Check for sufficient buffer size
211 if (i >= (line.size() - 3)) {
212 return false;
213 }
214
215 if ((line[i + 3] == 'J') && (_cursorHomePos != -1)) {
216 // Erase everything and rewind to home
217 const bool blocked = blockSignals(true);
218 for (int j = _cursorHomePos; j < rowCount(); j++) {
219 (void) setData(index(j), "");
220 }
221 (void) blockSignals(blocked);
222
223 const QVector<int> roles({Qt::DisplayRole, Qt::EditRole});
224 emit dataChanged(index(_cursorY), index(rowCount()), roles);
225 }
226
227 // Even if we didn't understand this ANSI code, remove the 4th char
228 (void) line.remove(i + 3,1);
229 break;
230 default:
231 continue;
232 }
233
234 // Remove the parsed ANSI code and decrement the bufferpos
235 (void) line.remove(i, 3);
236 i--;
237 }
238
239 return true;
240}
241
242QString MAVLinkConsoleController::_transformLineForRichText(const QString &line) const
243{
244 QString ret = line.toHtmlEscaped().replace(" ","&nbsp;").replace("\t", "&nbsp;&nbsp;&nbsp;&nbsp;");
245
246 if (ret.startsWith("WARN", Qt::CaseSensitive)) {
247 (void) ret.replace(0, 4, "<font color=\"" + _palette->colorOrange().name() + "\">WARN</font>");
248 } else if (ret.startsWith("ERROR", Qt::CaseSensitive)) {
249 (void) ret.replace(0, 5, "<font color=\"" + _palette->colorRed().name() + "\">ERROR</font>");
250 }
251
252 return ret;
253}
254
255QString MAVLinkConsoleController::_getText() const
256{
257 QString ret;
258 if (rowCount() > 0) {
259 ret = _transformLineForRichText(data(index(0), Qt::DisplayRole).toString());
260 }
261
262 for (int i = 1; i < rowCount(); ++i) {
263 ret += ("<br>" + _transformLineForRichText(data(index(i), Qt::DisplayRole).toString()));
264 }
265
266 return ret;
267}
268
269void MAVLinkConsoleController::_writeLine(int line, const QByteArray &text)
270{
271 const int rc = rowCount();
272 if (line >= rc) {
273 (void) insertRows(rc, 1 + line - rc);
274 }
275
276 if (rowCount() > kMaxNumLines) {
277 const int count = rowCount() - kMaxNumLines;
278 (void) removeRows(0, count);
279 line -= count;
280 _cursorY -= count;
281 _cursorHomePos -= count;
282 if (_cursorHomePos < 0) {
283 _cursorHomePos = -1;
284 }
285 }
286
287 const QModelIndex idx = index(line);
288 QString updated = data(idx, Qt::DisplayRole).toString();
289 (void) updated.replace(_cursorX, text.size(), text);
290 (void) setData(idx, updated);
291 _cursorX += text.size();
292}
293
294void MAVLinkConsoleController::CommandHistory::append(const QString &command)
295{
296 if (!command.isEmpty()) {
297 // do not append duplicates
298 if ((_history.isEmpty()) || (_history.last() != command)) {
299 if (_history.length() >= CommandHistory::kMaxHistoryLength) {
300 _history.removeFirst();
301 }
302 _history.append(command);
303 }
304 }
305
306 _index = _history.length();
307}
308
309QString MAVLinkConsoleController::CommandHistory::up(const QString &current)
310{
311 if (_index <= 0) {
312 return current;
313 }
314
315 --_index;
316 if (_index < _history.length()) {
317 return _history[_index];
318 }
319
320 return QStringLiteral("");
321}
322
323QString MAVLinkConsoleController::CommandHistory::down(const QString &current)
324{
325 if (_index >= _history.length()) {
326 return current;
327 }
328
329 ++_index;
330 if (_index < _history.length()) {
331 return _history[_index];
332 }
333
334 return QStringLiteral("");
335}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Q_INVOKABLE void sendCommand(const QString &command)
Q_INVOKABLE QString handleClipboard(const QString &command_pre)
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
static MultiVehicleManager * instance()
void activeVehicleChanged(Vehicle *activeVehicle)
QGCPalette is used in QML ui to expose color properties for the QGC palette.
Definition QGCPalette.h:83
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
int defaultComponentId() const
Definition Vehicle.h:670
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
bool close(int deviceId)