9#include <QtGui/QGuiApplication>
10#include <QtGui/QClipboard>
15 : QStringListModel(parent)
18 qCDebug(MAVLinkConsoleControllerLog) <<
this;
29 _sendSerialData(msg,
true);
32 qCDebug(MAVLinkConsoleControllerLog) <<
this;
37 QString output = command;
40 const QStringList lines = output.split(
'\n');
41 for (
const QString &line : lines) {
42 if (!line.isEmpty()) {
43 _history.append(line);
47 (void) output.append(
"\n");
48 _sendSerialData(qPrintable(output));
54 QString clipboardData = command_pre + QGuiApplication::clipboard()->text();
56 const int lastLinePos = clipboardData.lastIndexOf(
'\n');
57 if (lastLinePos != -1) {
58 const QString commands = clipboardData.mid(0, lastLinePos);
60 clipboardData = clipboardData.mid(lastLinePos + 1);
66void MAVLinkConsoleController::_setActiveVehicle(
Vehicle *vehicle)
68 for (QMetaObject::Connection &con : _connections) {
69 (void) disconnect(con);
75 _incomingBuffer.clear();
77 setStringList(QStringList());
85void MAVLinkConsoleController::_receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate,
const QByteArray &data)
87 Q_UNUSED(flags); Q_UNUSED(timeout); Q_UNUSED(baudrate);
89 if (device != SERIAL_CONTROL_DEV_SHELL) {
94 (void) _incomingBuffer.append(data);
96 while (!_incomingBuffer.isEmpty()) {
99 int idx = _incomingBuffer.indexOf(
'\n');
102 idx = _incomingBuffer.size();
107 QByteArray fragment = _incomingBuffer.mid(0, idx);
108 if (!_processANSItext(fragment)) {
113 _writeLine(_cursorY, fragment);
118 const int rc = rowCount();
119 if (_cursorY >= rc) {
120 (void) insertRows(rc, 1 + _cursorY - rc);
124 (void) _incomingBuffer.remove(0, idx + (newline ? 1 : 0));
128void MAVLinkConsoleController::_sendSerialData(
const QByteArray &data,
bool close)
131 qCWarning(MAVLinkConsoleControllerLog) <<
"Internal error";
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();
147 (void) chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(),
'\0');
149 const uint8_t flags =
close ? 0 : SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
152 (void) mavlink_msg_serial_control_pack_chan(
155 sharedLink->mavlinkChannel(),
157 SERIAL_CONTROL_DEV_SHELL,
162 reinterpret_cast<uint8_t*
>(chunk.data()),
168 (void) output.remove(0, chunk.size());
172bool MAVLinkConsoleController::_processANSItext(QByteArray &line)
175 for (
int i = 0; i < line.size(); i++) {
176 if (line[i] !=
'\x1B') {
181 if ((i >= (line.size() - 2)) || (line[i + 1] !=
'[')) {
187 switch (line[i + 2]) {
189 if (_cursorHomePos == -1) {
191 _cursorHomePos = _cursorY;
194 _cursorY = _cursorHomePos;
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()));
211 if (i >= (line.size() - 3)) {
215 if ((line[i + 3] ==
'J') && (_cursorHomePos != -1)) {
217 const bool blocked = blockSignals(
true);
218 for (
int j = _cursorHomePos; j < rowCount(); j++) {
219 (void) setData(index(j),
"");
221 (void) blockSignals(blocked);
223 const QVector<int> roles({Qt::DisplayRole, Qt::EditRole});
224 emit dataChanged(index(_cursorY), index(rowCount()), roles);
228 (void) line.remove(i + 3,1);
235 (void) line.remove(i, 3);
242QString MAVLinkConsoleController::_transformLineForRichText(
const QString &line)
const
244 QString ret = line.toHtmlEscaped().replace(
" ",
" ").replace(
"\t",
" ");
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>");
255QString MAVLinkConsoleController::_getText()
const
258 if (rowCount() > 0) {
259 ret = _transformLineForRichText(data(index(0), Qt::DisplayRole).toString());
262 for (
int i = 1; i < rowCount(); ++i) {
263 ret += (
"<br>" + _transformLineForRichText(data(index(i), Qt::DisplayRole).toString()));
269void MAVLinkConsoleController::_writeLine(
int line,
const QByteArray &text)
271 const int rc = rowCount();
273 (void) insertRows(rc, 1 + line - rc);
276 if (rowCount() > kMaxNumLines) {
277 const int count = rowCount() - kMaxNumLines;
278 (void) removeRows(0, count);
281 _cursorHomePos -= count;
282 if (_cursorHomePos < 0) {
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();
294void MAVLinkConsoleController::CommandHistory::append(
const QString &command)
296 if (!command.isEmpty()) {
298 if ((_history.isEmpty()) || (_history.last() != command)) {
299 if (_history.length() >= CommandHistory::kMaxHistoryLength) {
300 _history.removeFirst();
302 _history.append(command);
306 _index = _history.length();
309QString MAVLinkConsoleController::CommandHistory::up(
const QString ¤t)
316 if (_index < _history.length()) {
317 return _history[_index];
320 return QStringLiteral(
"");
323QString MAVLinkConsoleController::CommandHistory::down(
const QString ¤t)
325 if (_index >= _history.length()) {
330 if (_index < _history.length()) {
331 return _history[_index];
334 return QStringLiteral(
"");
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Q_INVOKABLE void sendCommand(const QString &command)
~MAVLinkConsoleController()
Q_INVOKABLE QString handleClipboard(const QString &command_pre)
static int getComponentId()
static MAVLinkProtocol * instance()
static MultiVehicleManager * instance()
void activeVehicleChanged(Vehicle *activeVehicle)
QGCPalette is used in QML ui to expose color properties for the QGC palette.
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)