From 273e57cb50685749c3f6702d7803180849022c21 Mon Sep 17 00:00:00 2001 From: Holden Date: Mon, 7 Oct 2024 15:53:57 -0400 Subject: [PATCH] AnalyzeView: Cleanup MAVLinkConsoleController --- src/AnalyzeView/MAVLinkConsoleController.cc | 363 ++++++++++---------- src/AnalyzeView/MAVLinkConsoleController.h | 89 +++-- src/AnalyzeView/MAVLinkConsolePage.qml | 136 ++++---- 3 files changed, 300 insertions(+), 288 deletions(-) diff --git a/src/AnalyzeView/MAVLinkConsoleController.cc b/src/AnalyzeView/MAVLinkConsoleController.cc index 13e73e3d481..44e6e15372a 100644 --- a/src/AnalyzeView/MAVLinkConsoleController.cc +++ b/src/AnalyzeView/MAVLinkConsoleController.cc @@ -8,23 +8,28 @@ ****************************************************************************/ #include "MAVLinkConsoleController.h" +#include "MAVLinkProtocol.h" +#include "MultiVehicleManager.h" #include "QGCApplication.h" +#include "QGCLoggingCategory.h" +#include "QGCPalette.h" #include "QGCToolbox.h" -#include "MultiVehicleManager.h" #include "Vehicle.h" -#include "MAVLinkProtocol.h" -#include "QGCLoggingCategory.h" #include #include QGC_LOGGING_CATEGORY(MAVLinkConsoleControllerLog, "qgc.analyzeview.mavlinkconsolecontroller") -MAVLinkConsoleController::MAVLinkConsoleController() - : QStringListModel() +MAVLinkConsoleController::MAVLinkConsoleController(QObject *parent) + : QStringListModel(parent) + , _palette(new QGCPalette(this)) { - auto *manager = qgcApp()->toolbox()->multiVehicleManager(); - connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle); + // qCDebug(MAVLinkConsoleControllerLog) << Q_FUNC_INFO << this; + + MultiVehicleManager *const manager = qgcApp()->toolbox()->multiVehicleManager(); + (void) connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle); + _setActiveVehicle(manager->activeVehicle()); } @@ -34,111 +39,107 @@ MAVLinkConsoleController::~MAVLinkConsoleController() QByteArray msg; _sendSerialData(msg, true); } + + // qCDebug(MAVLinkConsoleControllerLog) << Q_FUNC_INFO << this; } -void -MAVLinkConsoleController::sendCommand(QString command) +void MAVLinkConsoleController::sendCommand(const QString &command) { + QString output = command; + // there might be multiple commands, add them separately to the history - QStringList lines = command.split('\n'); - for (int i = 0; i < lines.size(); ++i) { - if (lines[i].size() > 0) { - _history.append(lines[i]); + const QStringList lines = output.split('\n'); + for (const QString &line : lines) { + if (!line.isEmpty()) { + _history.append(line); } } - command.append("\n"); - _sendSerialData(qPrintable(command)); - _cursor_home_pos = -1; -} - -QString -MAVLinkConsoleController::historyUp(const QString& current) -{ - return _history.up(current); -} -QString -MAVLinkConsoleController::historyDown(const QString& current) -{ - return _history.down(current); + (void) output.append("\n"); + _sendSerialData(qPrintable(output)); + _cursorHomePos = -1; } -QString -MAVLinkConsoleController::handleClipboard(const QString& command_pre) +QString MAVLinkConsoleController::handleClipboard(const QString &command_pre) { QString clipboardData = command_pre + QGuiApplication::clipboard()->text(); - int lastLinePos = clipboardData.lastIndexOf('\n'); + + const int lastLinePos = clipboardData.lastIndexOf('\n'); if (lastLinePos != -1) { - QString commands = clipboardData.mid(0, lastLinePos); + const QString commands = clipboardData.mid(0, lastLinePos); sendCommand(commands); - clipboardData = clipboardData.mid(lastLinePos+1); + clipboardData = clipboardData.mid(lastLinePos + 1); } + return clipboardData; } -void -MAVLinkConsoleController::_setActiveVehicle(Vehicle* vehicle) +void MAVLinkConsoleController::_setActiveVehicle(Vehicle *vehicle) { - for (auto &con : _uas_connections) - disconnect(con); - _uas_connections.clear(); + for (QMetaObject::Connection &con : _connections) { + (void) disconnect(con); + } + _connections.clear(); _vehicle = vehicle; - if (_vehicle) { - _incoming_buffer.clear(); + _incomingBuffer.clear(); // Reset the model setStringList(QStringList()); _cursorY = 0; _cursorX = 0; - _cursor_home_pos = -1; - _uas_connections << connect(_vehicle, &Vehicle::mavlinkSerialControl, this, &MAVLinkConsoleController::_receiveData); + _cursorHomePos = -1; + _connections << connect(_vehicle, &Vehicle::mavlinkSerialControl, this, &MAVLinkConsoleController::_receiveData); } } -void -MAVLinkConsoleController::_receiveData(uint8_t device, uint8_t, uint16_t, uint32_t, QByteArray data) +void MAVLinkConsoleController::_receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, const QByteArray &data) { - if (device != SERIAL_CONTROL_DEV_SHELL) + Q_UNUSED(flags); Q_UNUSED(timeout); Q_UNUSED(baudrate); + + if (device != SERIAL_CONTROL_DEV_SHELL) { return; + } // Append incoming data and parse for ANSI codes - _incoming_buffer.append(data); - while(!_incoming_buffer.isEmpty()) { + (void) _incomingBuffer.append(data); + + while (!_incomingBuffer.isEmpty()) { bool newline = false; - int idx = _incoming_buffer.indexOf('\n'); + + int idx = _incomingBuffer.indexOf('\n'); if (idx == -1) { // Read the whole incoming buffer - idx = _incoming_buffer.size(); + idx = _incomingBuffer.size(); } else { newline = true; } - QByteArray fragment = _incoming_buffer.mid(0, idx); - if (_processANSItext(fragment)) { - writeLine(_cursorY, fragment); - if (newline) { - _cursorY++; - _cursorX = 0; - // ensure line exists - int rc = rowCount(); - if (_cursorY >= rc) { - insertRows(rc, 1 + _cursorY - rc); - } - } - _incoming_buffer.remove(0, idx + (newline ? 1 : 0)); - } else { + QByteArray fragment = _incomingBuffer.mid(0, idx); + if (!_processANSItext(fragment)) { // ANSI processing failed, need more data return; } + + _writeLine(_cursorY, fragment); + if (newline) { + _cursorY++; + _cursorX = 0; + // ensure line exists + const int rc = rowCount(); + if (_cursorY >= rc) { + (void) insertRows(rc, 1 + _cursorY - rc); + } + } + + (void) _incomingBuffer.remove(0, idx + (newline ? 1 : 0)); } } -void -MAVLinkConsoleController::_sendSerialData(QByteArray data, bool close) +void MAVLinkConsoleController::_sendSerialData(const QByteArray &data, bool close) { if (!_vehicle) { - qWarning() << "Internal error"; + qCWarning(MAVLinkConsoleControllerLog) << "Internal error"; return; } @@ -148,184 +149,200 @@ MAVLinkConsoleController::_sendSerialData(QByteArray data, bool close) } // Send maximum sized chunks until the complete buffer is transmitted - while(data.size()) { - QByteArray chunk{data.left(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN)}; - int dataSize = chunk.size(); + QByteArray output(data); + while (output.size()) { + QByteArray chunk(data.left(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN)); + const int dataSize = chunk.size(); + // Ensure the buffer is large enough, as the MAVLink parser expects MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN bytes - chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(), '\0'); - uint8_t flags = SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI; - if (close) flags = 0; - auto protocol = qgcApp()->toolbox()->mavlinkProtocol(); - auto link = _vehicle->vehicleLinkManager()->primaryLink(); + (void) chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(), '\0'); + + const uint8_t flags = close ? 0 : SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI; + + MAVLinkProtocol *const protocol = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg; - mavlink_msg_serial_control_pack_chan( - protocol->getSystemId(), - protocol->getComponentId(), - sharedLink->mavlinkChannel(), - &msg, - SERIAL_CONTROL_DEV_SHELL, - flags, - 0, - 0, - dataSize, - reinterpret_cast(chunk.data()), - _vehicle->id(), _vehicle->defaultComponentId()); - _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); - data.remove(0, chunk.size()); + (void) mavlink_msg_serial_control_pack_chan( + protocol->getSystemId(), + protocol->getComponentId(), + sharedLink->mavlinkChannel(), + &msg, + SERIAL_CONTROL_DEV_SHELL, + flags, + 0, + 0, + dataSize, + reinterpret_cast(chunk.data()), + _vehicle->id(), + _vehicle->defaultComponentId() + ); + + (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); + (void) output.remove(0, chunk.size()); } } -bool -MAVLinkConsoleController::_processANSItext(QByteArray &line) +bool MAVLinkConsoleController::_processANSItext(QByteArray &line) { // Iterate over the incoming buffer to parse off known ANSI control codes for (int i = 0; i < line.size(); i++) { - if (line.at(i) == '\x1B') { - // For ANSI codes we expect at least 3 incoming chars - if (i < line.size() - 2 && line.at(i+1) == '[') { - // Parse ANSI code - switch(line.at(i+2)) { - default: - continue; - case 'H': - if (_cursor_home_pos == -1) { - // Assign new home position if home is unset - _cursor_home_pos = _cursorY; - } else { - // Rewind write cursor position to home - _cursorY = _cursor_home_pos; - _cursorX = 0; - } - break; - case 'K': - // Erase the current line to the end - if (_cursorY < rowCount()) { - auto idx = index(_cursorY); - QString updated = data(idx, Qt::DisplayRole).toString(); - int eraseIdx = _cursorX + i; - if (eraseIdx < updated.length()) { - setData(idx, updated.remove(eraseIdx, updated.length())); - } - } - break; - case '2': - // Check for sufficient buffer size - if ( i >= line.size() - 3) - return false; - - if (line.at(i+3) == 'J' && _cursor_home_pos != -1) { - // Erase everything and rewind to home - bool blocked = blockSignals(true); - for (int j = _cursor_home_pos; j < rowCount(); j++) - setData(index(j), ""); - blockSignals(blocked); - QVector roles({Qt::DisplayRole, Qt::EditRole}); - emit dataChanged(index(_cursorY), index(rowCount()), roles); - } - // Even if we didn't understand this ANSI code, remove the 4th char - line.remove(i+3,1); - break; - } - // Remove the parsed ANSI code and decrement the bufferpos - line.remove(i, 3); - i--; + if (line[i] != '\x1B') { + continue; + } + + // For ANSI codes we expect at least 3 incoming chars + if ((i >= (line.size() - 2)) || (line[i + 1] != '[')) { + // We can reasonably expect a control code was fragemented + // Stop parsing here and wait for it to come in + return false; + } + + switch (line[i + 2]) { + case 'H': + if (_cursorHomePos == -1) { + // Assign new home position if home is unset + _cursorHomePos = _cursorY; } else { - // We can reasonably expect a control code was fragemented - // Stop parsing here and wait for it to come in + // Rewind write cursor position to home + _cursorY = _cursorHomePos; + _cursorX = 0; + } + break; + case 'K': + // Erase the current line to the end + if (_cursorY < rowCount()) { + const QModelIndex idx = index(_cursorY); + QString updated = data(idx, Qt::DisplayRole).toString(); + const int eraseIdx = _cursorX + i; + if (eraseIdx < updated.length()) { + (void) setData(idx, updated.remove(eraseIdx, updated.length())); + } + } + break; + case '2': + // Check for sufficient buffer size + if (i >= (line.size() - 3)) { return false; } + + if ((line[i + 3] == 'J') && (_cursorHomePos != -1)) { + // Erase everything and rewind to home + const bool blocked = blockSignals(true); + for (int j = _cursorHomePos; j < rowCount(); j++) { + (void) setData(index(j), ""); + } + (void) blockSignals(blocked); + + const QVector roles({Qt::DisplayRole, Qt::EditRole}); + emit dataChanged(index(_cursorY), index(rowCount()), roles); + } + + // Even if we didn't understand this ANSI code, remove the 4th char + (void) line.remove(i + 3,1); + break; + default: + continue; } + + // Remove the parsed ANSI code and decrement the bufferpos + (void) line.remove(i, 3); + i--; } + return true; } -QString -MAVLinkConsoleController::transformLineForRichText(const QString& line) const +QString MAVLinkConsoleController::_transformLineForRichText(const QString &line) const { QString ret = line.toHtmlEscaped().replace(" "," ").replace("\t", "    "); if (ret.startsWith("WARN", Qt::CaseSensitive)) { - ret.replace(0, 4, "WARN"); + (void) ret.replace(0, 4, "colorOrange().name() + "\">WARN"); } else if (ret.startsWith("ERROR", Qt::CaseSensitive)) { - ret.replace(0, 5, "ERROR"); + (void) ret.replace(0, 5, "colorRed().name() + "\">ERROR"); } return ret; } -QString -MAVLinkConsoleController::getText() const +QString MAVLinkConsoleController::_getText() const { QString ret; if (rowCount() > 0) { - ret = transformLineForRichText(data(index(0), Qt::DisplayRole).toString()); + ret = _transformLineForRichText(data(index(0), Qt::DisplayRole).toString()); } + for (int i = 1; i < rowCount(); ++i) { - ret += "
" + transformLineForRichText(data(index(i), Qt::DisplayRole).toString()); + ret += ("
" + _transformLineForRichText(data(index(i), Qt::DisplayRole).toString())); } return ret; } -void -MAVLinkConsoleController::writeLine(int line, const QByteArray &text) +void MAVLinkConsoleController::_writeLine(int line, const QByteArray &text) { - auto rc = rowCount(); + const int rc = rowCount(); if (line >= rc) { - insertRows(rc, 1 + line - rc); + (void) insertRows(rc, 1 + line - rc); } - if (rowCount() > _max_num_lines) { - int count = rowCount() - _max_num_lines; - removeRows(0, count); + + if (rowCount() > kMaxNumLines) { + const int count = rowCount() - kMaxNumLines; + (void) removeRows(0, count); line -= count; _cursorY -= count; - _cursor_home_pos -= count; - if (_cursor_home_pos < 0) - _cursor_home_pos = -1; + _cursorHomePos -= count; + if (_cursorHomePos < 0) { + _cursorHomePos = -1; + } } - auto idx = index(line); + + const QModelIndex idx = index(line); QString updated = data(idx, Qt::DisplayRole).toString(); - updated.replace(_cursorX, text.size(), text); - setData(idx, updated); + (void) updated.replace(_cursorX, text.size(), text); + (void) setData(idx, updated); _cursorX += text.size(); } -void MAVLinkConsoleController::CommandHistory::append(const QString& command) +void MAVLinkConsoleController::CommandHistory::append(const QString &command) { - if (command.length() > 0) { - + if (!command.isEmpty()) { // do not append duplicates - if (_history.length() == 0 || _history.last() != command) { - - if (_history.length() >= maxHistoryLength) { + if ((_history.isEmpty()) || (_history.last() != command)) { + if (_history.length() >= CommandHistory::kMaxHistoryLength) { _history.removeFirst(); } _history.append(command); } } + _index = _history.length(); } -QString MAVLinkConsoleController::CommandHistory::up(const QString& current) +QString MAVLinkConsoleController::CommandHistory::up(const QString ¤t) { - if (_index <= 0) + if (_index <= 0) { return current; + } --_index; if (_index < _history.length()) { return _history[_index]; } - return ""; + + return QStringLiteral(""); } -QString MAVLinkConsoleController::CommandHistory::down(const QString& current) +QString MAVLinkConsoleController::CommandHistory::down(const QString ¤t) { - if (_index >= _history.length()) + if (_index >= _history.length()) { return current; + } ++_index; if (_index < _history.length()) { return _history[_index]; } - return ""; + + return QStringLiteral(""); } diff --git a/src/AnalyzeView/MAVLinkConsoleController.h b/src/AnalyzeView/MAVLinkConsoleController.h index 533360c7be8..5054f27dc0f 100644 --- a/src/AnalyzeView/MAVLinkConsoleController.h +++ b/src/AnalyzeView/MAVLinkConsoleController.h @@ -9,77 +9,70 @@ #pragma once +#include +#include #include #include -#include #include #include -#include - -#include "QGCPalette.h" Q_DECLARE_LOGGING_CATEGORY(MAVLinkConsoleControllerLog) +class QGCPalette; class Vehicle; -/// Controller for MavlinkConsole.qml. class MAVLinkConsoleController : public QStringListModel { Q_OBJECT QML_ELEMENT Q_MOC_INCLUDE("Vehicle.h") - -public: - MAVLinkConsoleController(); - virtual ~MAVLinkConsoleController(); - - Q_INVOKABLE void sendCommand(QString command); - - Q_INVOKABLE QString historyUp(const QString& current); - Q_INVOKABLE QString historyDown(const QString& current); - - /** - * Get clipboard data and if it has N lines, execute first N-1 commands - * @param command_pre prefix to data from clipboard - * @return last line of the clipboard data - */ - Q_INVOKABLE QString handleClipboard(const QString& command_pre); - - Q_PROPERTY(QString text READ getText CONSTANT) - -private slots: - void _setActiveVehicle (Vehicle* vehicle); - void _receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data); - -private: - bool _processANSItext(QByteArray &line); - void _sendSerialData(QByteArray, bool close = false); - void writeLine(int line, const QByteArray &text); - - QString transformLineForRichText(const QString& line) const; - - QString getText() const; + Q_PROPERTY(QString text READ _getText CONSTANT) class CommandHistory { public: - void append(const QString& command); - QString up(const QString& current); - QString down(const QString& current); + void append(const QString &command); + QString up(const QString ¤t); + QString down(const QString ¤t); + private: - static constexpr int maxHistoryLength = 100; QList _history; int _index = 0; + static constexpr int kMaxHistoryLength = 100; }; - static constexpr int _max_num_lines = 500; ///< history size (affects CPU load) +public: + explicit MAVLinkConsoleController(QObject *parent = nullptr); + ~MAVLinkConsoleController(); + + Q_INVOKABLE void sendCommand(const QString &command); + Q_INVOKABLE QString historyUp(const QString ¤t) { return _history.up(current); } + Q_INVOKABLE QString historyDown(const QString ¤t) { return _history.down(current); } - int _cursor_home_pos{-1}; - int _cursorY{0}; - int _cursorX{0}; - QByteArray _incoming_buffer; - Vehicle* _vehicle{nullptr}; - QList _uas_connections; + /// Get clipboard data and if it has N lines, execute first N-1 commands + /// @param command_pre prefix to data from clipboard + /// @return last line of the clipboard data + Q_INVOKABLE QString handleClipboard(const QString &command_pre); + +private slots: + void _setActiveVehicle(Vehicle *vehicle); + void _receiveData(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, const QByteArray &data); + +private: + bool _processANSItext(QByteArray &line); + void _sendSerialData(const QByteArray &data, bool close = false); + void _writeLine(int line, const QByteArray &text); + QString _transformLineForRichText(const QString &line) const; + QString _getText() const; + + QGCPalette *_palette = nullptr; + int _cursorHomePos = -1; + int _cursorY = 0; + int _cursorX = 0; + QByteArray _incomingBuffer; + QList _connections; CommandHistory _history; - QGCPalette _palette; + Vehicle *_vehicle = nullptr; + + static constexpr int kMaxNumLines = 500; ///< history size (affects CPU load) }; diff --git a/src/AnalyzeView/MAVLinkConsolePage.qml b/src/AnalyzeView/MAVLinkConsolePage.qml index a92bfa84cad..8b42acee569 100644 --- a/src/AnalyzeView/MAVLinkConsolePage.qml +++ b/src/AnalyzeView/MAVLinkConsolePage.qml @@ -9,22 +9,18 @@ import QtQuick import QtQuick.Controls -import QtQuick.Dialogs import QtQuick.Layouts import QGroundControl -import QGroundControl.Palette -import QGroundControl.FactSystem -import QGroundControl.FactControls import QGroundControl.Controls import QGroundControl.ScreenTools import QGroundControl.Controllers AnalyzePage { - id: mavlinkConsolePage - pageComponent: pageComponent - pageDescription: qsTr("Provides a connection to the vehicle's system shell.") - allowPopout: true + id: root + pageComponent: pageComponent + pageDescription: qsTr("Provides a connection to the vehicle's system shell.") + allowPopout: true property bool isLoaded: false @@ -32,40 +28,26 @@ AnalyzePage { // E.g. for android see https://bugreports.qt.io/browse/QTBUG-40803 readonly property bool _separateCommandInput: ScreenTools.isMobile - MAVLinkConsoleController { - id: conController - } + MAVLinkConsoleController { id: conController } Component { id: pageComponent ColumnLayout { - id: consoleColumn height: availableHeight - width: availableWidth - - Connections { - target: conController + width: availableWidth + property int _consoleOutputLen: 0 - onDataChanged: { - if (isLoaded) { - // rate-limit updates to reduce CPU load - updateTimer.start(); - } + function scrollToBottom() { + if (flickable.contentHeight > flickable.height) { + flickable.contentY = flickable.contentHeight - flickable.height } } - property int _consoleOutputLen: 0 + function getCommand() { return textConsole.getText(_consoleOutputLen, textConsole.length) } - function scrollToBottom() { - if (flickable.contentHeight > flickable.height) - flickable.contentY = flickable.contentHeight-flickable.height - } - function getCommand() { - return textConsole.getText(_consoleOutputLen, textConsole.length) - } function getCommandAndClear() { - var command = getCommand() + const command = getCommand() textConsole.remove(_consoleOutputLen, textConsole.length) return command } @@ -74,7 +56,7 @@ AnalyzePage { // we need to handle a few cases here: // in the general form we have: // and the clipboard may contain newlines - var cursor = textConsole.cursorPosition - _consoleOutputLen + const cursor = textConsole.cursorPosition - _consoleOutputLen var command = getCommandAndClear() var command_pre = "" var command_post = command @@ -87,6 +69,17 @@ AnalyzePage { textConsole.cursorPosition = textConsole.length - command_post.length } + Connections { + target: conController + + onDataChanged: { + if (isLoaded) { + // rate-limit updates to reduce CPU load + updateTimer.start(); + } + } + } + Timer { id: updateTimer interval: 30 @@ -96,8 +89,8 @@ AnalyzePage { // only update if scroll bar is at the bottom if (flickable.atYEnd) { // backup & restore cursor & command - var command = getCommand() - var cursor = textConsole.cursorPosition - _consoleOutputLen + const command = getCommand() + const cursor = textConsole.cursorPosition - _consoleOutputLen textConsole.text = conController.text _consoleOutputLen = textConsole.length textConsole.insert(textConsole.length, command) @@ -114,29 +107,29 @@ AnalyzePage { } QGCFlickable { - id: flickable - Layout.fillWidth: true - Layout.fillHeight: true - contentWidth: textConsole.width - contentHeight: textConsole.height + id: flickable + Layout.fillWidth: true + Layout.fillHeight: true + contentWidth: textConsole.width + contentHeight: textConsole.height TextArea.flickable: TextArea { - id: textConsole - width: availableWidth - wrapMode: Text.WordWrap - readOnly: _separateCommandInput - textFormat: TextEdit.RichText - inputMethodHints: Qt.ImhNoAutoUppercase | Qt.ImhMultiLine - text: "> " - focus: true - color: qgcPal.text - selectedTextColor: qgcPal.windowShade - selectionColor: qgcPal.text - font.pointSize: ScreenTools.defaultFontPointSize - font.family: ScreenTools.fixedFontFamily + id: textConsole + width: availableWidth + wrapMode: Text.WordWrap + readOnly: _separateCommandInput + textFormat: TextEdit.RichText + inputMethodHints: Qt.ImhNoAutoUppercase | Qt.ImhMultiLine + text: "> " + focus: true + color: qgcPal.text + selectedTextColor: qgcPal.windowShade + selectionColor: qgcPal.text + font.pointSize: ScreenTools.defaultFontPointSize + font.family: ScreenTools.fixedFontFamily Component.onCompleted: { - isLoaded = true + root.isLoaded = true _consoleOutputLen = textConsole.length textConsole.cursorPosition = _consoleOutputLen if (!_separateCommandInput) { @@ -147,11 +140,13 @@ AnalyzePage { background: Rectangle { color: qgcPal.windowShade } Keys.onPressed: (event) => { - if (event.key == Qt.Key_Tab) { // ignore tabs + // ignore tabs + if (event.key == Qt.Key_Tab) { event.accepted = true } + + // ignore for now if (event.matches(StandardKey.Cut)) { - // ignore for now event.accepted = true } @@ -194,25 +189,31 @@ AnalyzePage { if (textConsole.selectionStart < _consoleOutputLen) { textConsole.select(_consoleOutputLen, textConsole.selectionEnd) } + if (textConsole.cursorPosition < _consoleOutputLen) { textConsole.cursorPosition = textConsole.length } } - if (event.key == Qt.Key_Left) { + switch (event.key) { + case Qt.Key_Left: // don't move beyond current command if (textConsole.cursorPosition == _consoleOutputLen) { event.accepted = true } - } - if (event.key == Qt.Key_Backspace) { + break; + case Qt.Key_Backspace: if (textConsole.cursorPosition <= _consoleOutputLen) { event.accepted = true } - } - if (event.key == Qt.Key_Enter || event.key == Qt.Key_Return) { + break; + case Qt.Key_Enter: + case Qt.Key_Return: conController.sendCommand(getCommandAndClear()) event.accepted = true + break; + default: + break; } if (event.matches(StandardKey.Paste)) { @@ -222,12 +223,12 @@ AnalyzePage { // command history if (event.key == Qt.Key_Up) { - var command = conController.historyUp(getCommandAndClear()) + const command = conController.historyUp(getCommandAndClear()) textConsole.insert(textConsole.length, command) textConsole.cursorPosition = textConsole.length event.accepted = true } else if (event.key == Qt.Key_Down) { - var command = conController.historyDown(getCommandAndClear()) + const command = conController.historyDown(getCommandAndClear()) textConsole.insert(textConsole.length, command) textConsole.cursorPosition = textConsole.length event.accepted = true @@ -237,25 +238,26 @@ AnalyzePage { } RowLayout { - Layout.fillWidth: true - visible: _separateCommandInput + Layout.fillWidth: true + visible: _separateCommandInput + QGCTextField { - id: commandInput + id: commandInput Layout.fillWidth: true placeholderText: qsTr("Enter Commands here...") inputMethodHints: Qt.ImhNoAutoUppercase + onAccepted: sendCommand() function sendCommand() { conController.sendCommand(text) text = "" scrollToBottom() } - onAccepted: sendCommand() + } QGCButton { - id: sendButton - text: qsTr("Send") + text: qsTr("Send") onClicked: commandInput.sendCommand() } }