diff --git a/src/Waypoint.cc b/src/Waypoint.cc
index 1f42cd3..40447c1 100644
--- a/src/Waypoint.cc
+++ b/src/Waypoint.cc
@@ -55,8 +55,7 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1,
}
Waypoint::~Waypoint()
-{
-
+{
}
bool Waypoint::isNavigationType()
diff --git a/src/Waypoint.h b/src/Waypoint.h
index d029811..6f5477c 100644
--- a/src/Waypoint.h
+++ b/src/Waypoint.h
@@ -188,7 +188,7 @@ public slots:
signals:
/** @brief Announces a change to the waypoint data */
- void changed(Waypoint* wp);
+ void changed(Waypoint* wp);
};
#endif // WAYPOINT_H
diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc
index 5e87809..6119f43 100644
--- a/src/uas/UASWaypointManager.cc
+++ b/src/uas/UASWaypointManager.cc
@@ -133,11 +133,20 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
// // qDebug() << "got waypoint count (" << count << ") from ID " << systemId;
+ //Clear the old edit-list before receiving the new one
+ if (read_to_edit == true){
+ while(waypointsEditable.size()>0) {
+ Waypoint *t = waypointsEditable[0];
+ waypointsEditable.remove(0);
+ delete t;
+ }
+ emit waypointEditableListChanged();
+ }
+
if (count > 0) {
current_count = count;
current_wp_id = 0;
current_state = WP_GETLIST_GETWPS;
-
sendWaypointRequest(current_wp_id);
} else {
protocol_timer.stop();
@@ -149,6 +158,8 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
current_partner_systemid = 0;
current_partner_compid = 0;
}
+
+
} else {
qDebug("Rejecting message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d", current_state, WP_GETLIST, current_partner_systemid, systemId, current_partner_compid, compId);
}
@@ -766,20 +777,25 @@ void UASWaypointManager::readWaypoints(bool readToEdit)
emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE) {
+
//Clear the old view-list before receiving the new one
while(waypointsViewOnly.size()>0) {
- delete waypointsViewOnly.back();
- waypointsViewOnly.pop_back();
+ Waypoint *t = waypointsViewOnly[0];
+ waypointsViewOnly.remove(0);
+ delete t;
}
-
+ emit waypointViewOnlyListChanged();
+ /* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.size()>0) {
- delete waypointsEditable.back();
- waypointsEditable.pop_back();
+ Waypoint *t = waypointsEditable[0];
+ waypointsEditable.remove(0);
+ delete t;
}
+ emit waypointEditableListChanged();
}
-
+ */
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES;
diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc
index 0d1c4f5..ed3c8f1 100644
--- a/src/ui/WaypointEditableView.cc
+++ b/src/ui/WaypointEditableView.cc
@@ -20,10 +20,12 @@
#include "WaypointEditableView.h"
#include "ui_WaypointEditableView.h"
#include "ui_QGCCustomWaypointAction.h"
+#include "ui_QGCMissionDoWidget.h"
WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
QWidget(parent),
customCommand(new Ui_QGCCustomWaypointAction),
+ doCommand(new Ui_QGCMissionDoWidget),
viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV),
m_ui(new Ui::WaypointEditableView)
{
@@ -34,6 +36,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
// CUSTOM COMMAND WIDGET
customCommand->setupUi(m_ui->customActionWidget);
+ // DO COMMAND WIDGET
+ //doCommand->setupUi(m_ui->customActionWidget);
+
+
// add actions
m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT);
m_ui->comboBox_action->addItem(tr("NAV: TakeOff"),MAV_CMD_NAV_TAKEOFF);
@@ -142,6 +148,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 82);
m_ui->takeOffAngleSpinBox->show();
break;
@@ -154,6 +162,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 26);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
@@ -165,6 +175,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 26);
break;
case MAV_CMD_NAV_WAYPOINT:
@@ -173,6 +185,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->show();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 1);
m_ui->autoContinue->show();
@@ -187,6 +201,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 25);
m_ui->orbitSpinBox->show();
break;
@@ -197,6 +213,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show();
m_ui->turnsSpinBox->show();
@@ -208,6 +226,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
@@ -218,7 +238,8 @@ void WaypointEditableView::updateActionView(int action)
// m_ui->turnsSpinBox->hide();
// m_ui->holdTimeSpinBox->show();
// m_ui->customActionWidget->hide();
-
+// m_ui->missionDoWidgetSlot->hide();
+// m_ui->missionConditionWidgetSlot->hide();
// m_ui->autoContinue->show();
// m_ui->acceptanceSpinBox->hide();
// m_ui->yawSpinBox->hide();
@@ -259,6 +280,11 @@ void WaypointEditableView::changedAction(int index)
// Update view
updateActionView(actionIndex);
break;
+ case MAV_CMD_DO_JUMP:
+ {
+ changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DO);
+ break;
+ }
case MAV_CMD_ENUM_END:
default:
// Switch to mission frame
@@ -275,9 +301,32 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
case QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION:
// Hide everything, show condition widget
// TODO
+ break;
case QGC_WAYPOINTEDITABLEVIEW_MODE_DO:
+ {
+ // Hide almost everything
+ m_ui->orbitSpinBox->hide();
+ m_ui->takeOffAngleSpinBox->hide();
+ m_ui->yawSpinBox->hide();
+ m_ui->turnsSpinBox->hide();
+ m_ui->holdTimeSpinBox->hide();
+ m_ui->acceptanceSpinBox->hide();
+ m_ui->posDSpinBox->hide();
+ m_ui->posESpinBox->hide();
+ m_ui->posNSpinBox->hide();
+ m_ui->latSpinBox->hide();
+ m_ui->lonSpinBox->hide();
+ m_ui->altSpinBox->hide();
+ // Show action widget
+ if (!m_ui->missionDoWidgetSlot->isVisible()) {
+ m_ui->missionDoWidgetSlot->show();
+ }
+ if (!m_ui->autoContinue->isVisible()) {
+ m_ui->autoContinue->show();
+ }
break;
+ }
case QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING:
// Hide almost everything
m_ui->orbitSpinBox->hide();
@@ -324,6 +373,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
@@ -342,6 +393,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
+ m_ui->missionDoWidgetSlot->hide();
+ m_ui->missionConditionWidgetSlot->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
@@ -492,7 +545,7 @@ void WaypointEditableView::updateValues()
if (m_ui->posDSpinBox->value() != wp->getZ()) {
m_ui->posDSpinBox->setValue(wp->getZ());
}
- }
+ }
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT: {
diff --git a/src/ui/WaypointEditableView.h b/src/ui/WaypointEditableView.h
index 096559c..5a734ae 100644
--- a/src/ui/WaypointEditableView.h
+++ b/src/ui/WaypointEditableView.h
@@ -49,6 +49,7 @@ namespace Ui
class WaypointEditableView;
}
class Ui_QGCCustomWaypointAction;
+class Ui_QGCMissionDoWidget;
class WaypointEditableView : public QWidget
{
Q_OBJECT
@@ -82,7 +83,8 @@ protected:
Waypoint* wp;
// Special widgets extendending the
// waypoint view to mission capabilities
- Ui_QGCCustomWaypointAction* customCommand;
+ Ui_QGCCustomWaypointAction* customCommand;
+ Ui_QGCMissionDoWidget* doCommand;
QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
private:
diff --git a/src/ui/WaypointEditableView.ui b/src/ui/WaypointEditableView.ui
index 29ed36f..0d58c6d 100644
--- a/src/ui/WaypointEditableView.ui
+++ b/src/ui/WaypointEditableView.ui
@@ -7,7 +7,7 @@
0
0
2208
- 39
+ 37
@@ -96,7 +96,7 @@ QPushButton:pressed {
-
+
2
@@ -121,10 +121,10 @@ QPushButton:pressed {
Qt::TabFocus
- Currently selected waypoint
+ Mission Start
- Currently selected waypoint
+ Mission Start
@@ -594,7 +594,33 @@ where to accept this waypoint as reached
-
-
+
+ 0
+ 0
+
+
+
+
+ 0
+ 0
+
+
+
+
+ -
+
+
+
+ 0
+ 0
+
+
+
+
+ -
+
+
+
0
0
diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc
index 1dd9968..808cbf5 100644
--- a/src/ui/WaypointViewOnlyView.cc
+++ b/src/ui/WaypointViewOnlyView.cc
@@ -15,65 +15,62 @@ WaypointViewOnlyView::WaypointViewOnlyView(Waypoint* wp, QWidget *parent) :
}
void WaypointViewOnlyView::changedAutoContinue(int state)
-{
+{
bool new_value = false;
if (state != 0)
{
new_value = true;
}
- m_ui->autoContinue->blockSignals(true);
- m_ui->autoContinue->setChecked(state);
- m_ui->autoContinue->blockSignals(false);
- wp->setAutocontinue(new_value);
+ wp->setAutocontinue(new_value);
emit changeAutoContinue(wp->getId(),new_value);
}
void WaypointViewOnlyView::changedCurrent(int state)
+//This is a slot receiving signals from QCheckBox m_ui->current. The state given here is whatever the user has clicked and not the true "current" value onboard.
{
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
- m_ui->current->blockSignals(true);
- if (state == 0)
- {
- /*
-
- m_ui->current->setStyleSheet("");
+ m_ui->current->blockSignals(true);
- */
- if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current
+ if (m_ui->current->isChecked() == false)
+ {
+ if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current. Box stays checked
{
- m_ui->current->setChecked(true);
m_ui->current->setCheckState(Qt::Checked);
+ qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Rechecked true. stay true " << m_ui->current->isChecked();
}
- else
+ else // Strange case, unchecking the box which was not checked to start with
{
- m_ui->current->setChecked(false);
- m_ui->current->setCheckState(Qt::Unchecked);
- wp->setCurrent(false);
+ m_ui->current->setCheckState(Qt::Unchecked);
+ qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Unchecked false. set false " << m_ui->current->isChecked();
}
}
else
- {
- /*
- FIXME: The checkbox should turn gray to indicate, that set_current request has been sent to UAV. It should become blue (checked) after receiving set_current_ack from waypointplanner.
-
- m_ui->current->setStyleSheet("*::indicator { \
- border: 1px solid #777777; \
- border-radius: 2px; \
- color: #999999; \
- width: 10px; \
- height: 10px; \
- }");
- */
- wp->setCurrent(true);
+ {
+ hightlightDesiredCurrent(true);
+ m_ui->current->setCheckState(Qt::Unchecked);
+ qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Checked new. Sending set_current request to Manager " << m_ui->current->isChecked();
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
+
}
m_ui->current->blockSignals(false);
}
void WaypointViewOnlyView::setCurrent(bool state)
+//This is a slot receiving signals from UASWaypointManager. The state given here is the true representation of what the "current" waypoint on UAV is.
{
- m_ui->current->blockSignals(true);
- m_ui->current->setChecked(state);
+ m_ui->current->blockSignals(true);
+ if (state == true)
+ {
+ wp->setCurrent(true);
+ hightlightDesiredCurrent(true);
+ m_ui->current->setCheckState(Qt::Checked);
+ }
+ else
+ {
+ wp->setCurrent(false);
+ hightlightDesiredCurrent(false);
+ m_ui->current->setCheckState(Qt::Unchecked);
+ }
m_ui->current->blockSignals(false);
}
@@ -159,12 +156,11 @@ void WaypointViewOnlyView::updateValues()
}
}
-
-
+ hightlightDesiredCurrent(wp->getCurrent());
if (m_ui->current->isChecked() != wp->getCurrent())
{
m_ui->current->blockSignals(true);
- m_ui->current->setChecked(wp->getCurrent());
+ m_ui->current->setChecked(wp->getCurrent());
m_ui->current->blockSignals(false);
}
if (m_ui->autoContinue->isChecked() != wp->getAutoContinue())
@@ -406,6 +402,30 @@ void WaypointViewOnlyView::updateValues()
}
}
+void WaypointViewOnlyView::hightlightDesiredCurrent(bool hightlight_on)
+{
+ QColor backGroundColor = QGC::colorBackground;
+ QString checkBoxStyle;
+ if (wp->getId() % 2 == 1)
+ {
+ backGroundColor = QColor("#252528").lighter(150);
+ }
+ else
+ {
+ backGroundColor = QColor("#252528").lighter(250);
+ }
+
+ if (hightlight_on)
+ {
+ checkBoxStyle = QString("QCheckBox {background-color: %1; color: #454545; border-color: #EEEEEE; } QCheckBox::indicator { border-color: #FFFFFF}").arg(backGroundColor.name());
+ }
+ else
+ {
+ checkBoxStyle = QString("QCheckBox {background-color: %1; color: #454545; border-color: #EEEEEE; } QCheckBox::indicator { border-color: QGC::colorBackground}").arg(backGroundColor.name());
+ }
+ m_ui->current->setStyleSheet(checkBoxStyle);
+}
+
WaypointViewOnlyView::~WaypointViewOnlyView()
{
delete m_ui;
diff --git a/src/ui/WaypointViewOnlyView.h b/src/ui/WaypointViewOnlyView.h
index 099a3d8..81f3e9a 100644
--- a/src/ui/WaypointViewOnlyView.h
+++ b/src/ui/WaypointViewOnlyView.h
@@ -31,6 +31,7 @@ protected:
Waypoint* wp;
private:
+ void hightlightDesiredCurrent(bool hightlight_on);
Ui::WaypointViewOnlyView *m_ui;
};
diff --git a/src/ui/WaypointViewOnlyView.ui b/src/ui/WaypointViewOnlyView.ui
index 76ef552..da30a97 100644
--- a/src/ui/WaypointViewOnlyView.ui
+++ b/src/ui/WaypointViewOnlyView.ui
@@ -96,6 +96,421 @@ margin-top: 1ex; /* leave space at the top for the title */
0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 255
+ 0
+
+
+
+
+
+
+ 0
+ 212
+ 0
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 0
+ 113
+ 0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 127
+ 212
+ 127
+
+
+
+
+
+
+ 255
+ 255
+ 220
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 255
+ 0
+
+
+
+
+
+
+ 0
+ 212
+ 0
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 0
+ 113
+ 0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 127
+ 212
+ 127
+
+
+
+
+
+
+ 255
+ 255
+ 220
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 255
+ 0
+
+
+
+
+
+
+ 0
+ 212
+ 0
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 0
+ 113
+ 0
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 255
+
+
+
+
+
+
+ 0
+ 85
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
+ 0
+ 170
+ 0
+
+
+
+
+
+
+ 255
+ 255
+ 220
+
+
+
+
+
+
+ 0
+ 0
+ 0
+
+
+
+
+
+
Currently executed waypoint