diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 6fff0b851c58b018cf8e82cffe68af82c039dd5d..98f74b81556fa1f302c0e5521c883862348c4184 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2095,7 +2095,7 @@ void UAS::halt() { mavlink_message_t msg; // TODO Replace MG System ID with static function call and allow to change ID in GUI - mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT); + mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HOLD); // Send message twice to increase chance of reception sendMessage(msg); sendMessage(msg); diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 826761c70d4d537368005224c0c79664805af7c5..2c36172714e6fa7a20e73c1268ac58bf1ff5c072 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -103,7 +103,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) : userSetPointSet(false), dragStarted(false), leftDragStarted(false), - mouseHasMoved(false) + mouseHasMoved(false), + actionPending(false) { refreshTimer->setInterval(updateInterval); @@ -568,10 +569,10 @@ void HSIDisplay::mouseReleaseEvent(QMouseEvent * event) { if (leftDragStarted) { - qDebug() << "Z CHANGED" << uiZSetCoordinate; - setStatusMessage(QString("SENT NEW Z: %1").arg(uiZSetCoordinate)); - setBodySetpointCoordinateZ(uiZSetCoordinate); - leftDragStarted = false; +// qDebug() << "Z CHANGED" << uiZSetCoordinate; +// setStatusMessage(QString("SENT NEW Z: %1").arg(uiZSetCoordinate)); +// setBodySetpointCoordinateZ(uiZSetCoordinate); +// leftDragStarted = false; } } } @@ -606,14 +607,29 @@ void HSIDisplay::mouseMoveEvent(QMouseEvent * event) if (leftDragStarted) { - uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height(); - setStatusMessage(QString("NEW Z: %1").arg(uiZSetCoordinate)); +// uiZSetCoordinate -= 0.06f*(startY - event->y()) / this->frameSize().height(); +// setStatusMessage(QString("NEW Z: %1").arg(uiZSetCoordinate)); } if (leftDragStarted || dragStarted) mouseHasMoved = true; } } +void HSIDisplay::keyPressEvent(QKeyEvent* event) +{ + if (event->key() == Qt::Key_Enter || event->key() == Qt::Key_S) + { + actionPending = false; + statusMessage = "SETPOINT SENT"; + statusClearTimer.start(); + sendBodySetPointCoordinates(); + } + else + { + HDDisplay::keyPressEvent(event); + } +} + void HSIDisplay::contextMenuEvent (QContextMenuEvent* event) { event->ignore(); @@ -703,7 +719,10 @@ void HSIDisplay::setBodySetpointCoordinateXY(double x, double y) if (uas && mavInitialized) { - sendBodySetPointCoordinates(); + //sendBodySetPointCoordinates(); + statusMessage = "POSITION SET, PRESS TO SEND"; + actionPending = true; + statusClearTimer.start(); qDebug() << "Setting new setpoint at x: " << x << "metric y:" << y; } } @@ -713,7 +732,10 @@ void HSIDisplay::setBodySetpointCoordinateZ(double z) userSetPointSet = true; // Set coordinates and send them out to MAV uiZSetCoordinate = z; - sendBodySetPointCoordinates(); + statusMessage = "Z SET, PRESS TO SEND"; + actionPending = true; + statusClearTimer.start(); + //sendBodySetPointCoordinates(); } void HSIDisplay::setBodySetpointCoordinateYaw(double yaw) @@ -733,7 +755,10 @@ void HSIDisplay::setBodySetpointCoordinateYaw(double yaw) // Set coordinates and send them out to MAV uiYawSet = atan2(sin(yaw), cos(yaw)); qDebug() << "YAW IN" << yaw << "YAW OUT" << uiYawSet; - sendBodySetPointCoordinates(); + statusMessage = "YAW SET, PRESS TO SEND"; + statusClearTimer.start(); + actionPending = true; + //sendBodySetPointCoordinates(); } void HSIDisplay::sendBodySetPointCoordinates() @@ -791,7 +816,7 @@ void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesir { uiXSetCoordinate = bodyXSetCoordinate; uiYSetCoordinate = bodyYSetCoordinate; - uiZSetCoordinate = bodyZSetCoordinate; +// uiZSetCoordinate = bodyZSetCoordinate; uiYawSet= bodyYawSet; } } diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h index 585a69513dab3fba3a95df9c98bb8d151fc24932..ac3c3aeaf7515ef88364838d22cd3da60ba6225e 100644 --- a/src/ui/HSIDisplay.h +++ b/src/ui/HSIDisplay.h @@ -89,6 +89,7 @@ public slots: void clearStatusMessage() { statusMessage = ""; + actionPending = false; } signals: @@ -123,6 +124,8 @@ protected slots: void mouseMoveEvent(QMouseEvent * event); /** @brief Receive mouse wheel events */ void wheelEvent(QWheelEvent* event); + /** @brief Read out send keys */ + void keyPressEvent(QKeyEvent* event); /** @brief Ignore context menu event */ void contextMenuEvent (QContextMenuEvent* event); /** @brief Set status message on screen */ @@ -166,6 +169,7 @@ protected: float startY; QTimer statusClearTimer; QString statusMessage; + bool actionPending; /** * @brief Private data container class to be used within the HSI widget