Commit 57ef8d67 authored by Don Gagne's avatar Don Gagne

Merge pull request #1995 from DonLakeFlyer/HomePositionFixes

Home position fixes
parents 1c552042 24ae7b64
......@@ -142,52 +142,6 @@ void MissionEditor::removeMissionItem(int index)
_recalcAll();
}
void MissionEditor::moveUp(int index)
{
if (!_canEdit) {
qWarning() << "addMissionItem called with _canEdit == false";
return;
}
if (_missionItems->count() < 2 || index <= 0 || index >= _missionItems->count()) {
return;
}
MissionItem item1 = *qobject_cast<MissionItem*>(_missionItems->get(index - 1));
MissionItem item2 = *qobject_cast<MissionItem*>(_missionItems->get(index));
_missionItems->removeAt(index - 1);
_missionItems->removeAt(index - 1);
_missionItems->insert(index - 1, new MissionItem(item2, _missionItems));
_missionItems->insert(index, new MissionItem(item1, _missionItems));
_recalcAll();
}
void MissionEditor::moveDown(int index)
{
if (!_canEdit) {
qWarning() << "addMissionItem called with _canEdit == false";
return;
}
if (_missionItems->count() < 2 || index >= _missionItems->count() - 1) {
return;
}
MissionItem item1 = *qobject_cast<MissionItem*>(_missionItems->get(index));
MissionItem item2 = *qobject_cast<MissionItem*>(_missionItems->get(index + 1));
_missionItems->removeAt(index);
_missionItems->removeAt(index);
_missionItems->insert(index, new MissionItem(item2, _missionItems));
_missionItems->insert(index + 1, new MissionItem(item1, _missionItems));
_recalcAll();
}
void MissionEditor::loadMissionFromFile(void)
{
QString errorString;
......
......@@ -48,8 +48,6 @@ public:
Q_INVOKABLE void loadMissionFromFile(void);
Q_INVOKABLE void saveMissionToFile(void);
Q_INVOKABLE void removeMissionItem(int index);
Q_INVOKABLE void moveUp(int index);
Q_INVOKABLE void moveDown(int index);
// Property accessors
......
......@@ -440,6 +440,7 @@ QGCView {
MissionItemEditor {
missionItem: object
width: parent.width
readOnly: object.sequenceNumber == 0 && liveHomePositionAvailable
onClicked: setCurrentItem(object.sequenceNumber)
......@@ -451,9 +452,6 @@ QGCView {
setCurrentItem(newCurrentItem)
}
}
onMoveUp: controller.moveUp(object.sequenceNumber)
onMoveDown: controller.moveDown(object.sequenceNumber)
}
} // ListView
......
......@@ -448,9 +448,11 @@ bool QGCApplication::_initForNormalAppBoot(void)
splashScreen->finish(mainWindow);
mainWindow->splashScreenFinished();
#ifndef __mobile__
// Now that main window is up check for lost log files
connect(this, &QGCApplication::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles);
emit checkForLostLogFiles();
#endif
// Load known link configurations
LinkManager::instance()->loadLinkConfigurationList();
......
......@@ -13,17 +13,16 @@ import QGroundControl.Palette 1.0
Rectangle {
id: _root
property var missionItem
property var missionItem ///< MissionItem associated with this editor
property bool readOnly ///< true: read only view, false: full editing view
signal clicked
signal remove
signal moveUp
signal moveDown
height: missionItem.isCurrentItem ?
(missionItem.textFieldFacts.count * (measureTextField.height + _margin)) +
(missionItem.checkboxFacts.count * (measureCheckbox.height + _margin)) +
commandPicker.height + deleteButton.height + (_margin * 9) :
commandPicker.height + (deleteButton.visible ? deleteButton.height : 0) + (_margin * 9) :
commandPicker.height + (_margin * 2)
color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
......@@ -63,7 +62,6 @@ Rectangle {
onClicked: _root.clicked()
}
QGCComboBox {
id: commandPicker
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 10
......@@ -71,7 +69,7 @@ Rectangle {
anchors.right: parent.right
currentIndex: missionItem.commandByIndex
model: missionItem.commandNames
visible: missionItem.sequenceNumber != 0
visible: missionItem.sequenceNumber != 0 // Item 0 is home position, can't change item type
onActivated: missionItem.commandByIndex = index
}
......@@ -79,7 +77,7 @@ Rectangle {
Rectangle {
anchors.fill: commandPicker
color: qgcPal.button
visible: missionItem.sequenceNumber == 0
visible: missionItem.sequenceNumber == 0 // Item 0 is home position, can't change item type
QGCLabel {
id: homeLabel
......@@ -119,6 +117,7 @@ Rectangle {
height: textField.height
QGCLabel {
id: textFieldLabel
anchors.baseline: textField.baseline
text: object.name
}
......@@ -129,6 +128,14 @@ Rectangle {
width: _editFieldWidth
showUnits: true
fact: object
visible: !_root.readOnly
}
FactLabel {
anchors.baseline: textFieldLabel.baseline
anchors.right: parent.right
fact: object
visible: _root.readOnly
}
}
}
......@@ -160,26 +167,13 @@ Rectangle {
readonly property real buttonWidth: (width - (_margin * 2)) / 3
QGCButton {
id: deleteButton
width: parent.buttonWidth
text: "Delete"
id: deleteButton
width: parent.buttonWidth
text: "Delete"
visible: !readOnly
onClicked: _root.remove()
}
QGCButton {
width: parent.buttonWidth
text: "Up"
onClicked: _root.moveUp()
}
QGCButton {
width: parent.buttonWidth
text: "Down"
onClicked: _root.moveDown()
}
}
} // Column
......
......@@ -367,7 +367,9 @@ void LogReplayLink::_play(void)
{
// FIXME: With move to link I don't think this is needed any more? Except for the replay widget handling multi-uas?
LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
#ifndef __mobile__
MAVLinkProtocol::instance()->suspendLogForReplay(true);
#endif
// Make sure we aren't at the end of the file, if we are, reset to the beginning and play from there.
if (_logFile.atEnd()) {
......@@ -397,7 +399,9 @@ void LogReplayLink::_play(void)
void LogReplayLink::_pause(void)
{
LinkManager::instance()->setConnectionsAllowed();
#ifndef __mobile__
MAVLinkProtocol::instance()->suspendLogForReplay(false);
#endif
_readTickTimer.stop();
......
......@@ -33,8 +33,10 @@ Q_DECLARE_METATYPE(mavlink_message_t)
IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol)
QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog")
#ifndef __mobile__
const char* MAVLinkProtocol::_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file
const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Extension for log files
#endif
/**
* The default constructor will create a new MAVLink object sending heartbeats at
......@@ -52,10 +54,12 @@ MAVLinkProtocol::MAVLinkProtocol(QObject* parent) :
m_actionRetransmissionTimeout(100),
versionMismatchIgnore(false),
systemId(QGC::defaultSystemId),
#ifndef __mobile__
_logSuspendError(false),
_logSuspendReplay(false),
_logWasArmed(false),
_tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)),
#endif
_linkMgr(LinkManager::instance()),
_heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
_heartbeatsEnabled(true)
......@@ -91,7 +95,9 @@ MAVLinkProtocol::~MAVLinkProtocol()
{
storeSettings();
#ifndef __mobile__
_closeLogFile();
#endif
}
void MAVLinkProtocol::loadSettings()
......@@ -181,10 +187,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
// Use the same shared pointer as LinkManager
_connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link));
#ifndef __mobile__
if (_connectedLinks.count() == 1) {
// This is the first link, we need to start logging
_startLogging();
}
#endif
// Send command to start MAVLink
// XXX hacky but safe
......@@ -206,10 +214,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
Q_UNUSED(found);
Q_ASSERT(found);
#ifndef __mobile__
if (_connectedLinks.count() == 0) {
// Last link is gone, close out logging
_stopLogging();
}
#endif
}
}
......@@ -303,6 +313,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
rstatus.txbuf, rstatus.noise, rstatus.remnoise);
}
#ifndef __mobile__
// Log data
if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) {
......@@ -339,6 +350,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
}
}
#endif
if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
// Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
......@@ -613,6 +625,7 @@ int MAVLinkProtocol::getHeartbeatRate()
return _heartbeatRate;
}
#ifndef __mobile__
/// @brief Closes the log file if it is open
bool MAVLinkProtocol::_closeLogFile(void)
{
......@@ -707,3 +720,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void)
QFile::remove(fileInfo.filePath());
}
}
#endif
......@@ -203,11 +203,13 @@ public slots:
/** @brief Store protocol settings */
void storeSettings();
#ifndef __mobile__
/// @brief Deletes any log files which are in the temp directory
static void deleteTempLogFiles(void);
/// Checks for lost log files
void checkForLostLogFiles(void);
#endif
protected:
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
......@@ -281,22 +283,25 @@ private:
~MAVLinkProtocol();
void _linkStatusChanged(LinkInterface* link, bool connected);
#ifndef __mobile__
bool _closeLogFile(void);
void _startLogging(void);
void _stopLogging(void);
/// List of all links connected to protocol. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList<SharedLinkInterface> _connectedLinks;
bool _logSuspendError; ///< true: Logging suspended due to error
bool _logSuspendReplay; ///< true: Logging suspended due to replay
bool _logWasArmed; ///< true: vehicle was armed during logging
QGCTemporaryFile _tempLogFile; ///< File to log to
static const char* _tempLogFileTemplate; ///< Template for temporary log file
static const char* _logFileExtension; ///< Extension for log files
#endif
/// List of all links connected to protocol. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList<SharedLinkInterface> _connectedLinks;
LinkManager* _linkMgr;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment