Commit 2bb0b1e6 authored by QGroundControl's avatar QGroundControl

Merge pull request #101 from Trof/offline-wplist

Offline wplist
parents 2f7de027 aa5d5043
...@@ -56,7 +56,6 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1, ...@@ -56,7 +56,6 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1,
Waypoint::~Waypoint() Waypoint::~Waypoint()
{ {
} }
bool Waypoint::isNavigationType() bool Waypoint::isNavigationType()
......
...@@ -133,11 +133,20 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui ...@@ -133,11 +133,20 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
// // qDebug() << "got waypoint count (" << count << ") from ID " << systemId; // // 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) { if (count > 0) {
current_count = count; current_count = count;
current_wp_id = 0; current_wp_id = 0;
current_state = WP_GETLIST_GETWPS; current_state = WP_GETLIST_GETWPS;
sendWaypointRequest(current_wp_id); sendWaypointRequest(current_wp_id);
} else { } else {
protocol_timer.stop(); protocol_timer.stop();
...@@ -149,6 +158,8 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui ...@@ -149,6 +158,8 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
current_partner_systemid = 0; current_partner_systemid = 0;
current_partner_compid = 0; current_partner_compid = 0;
} }
} else { } 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); 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) ...@@ -766,20 +777,25 @@ void UASWaypointManager::readWaypoints(bool readToEdit)
emit readGlobalWPFromUAS(true); emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE) { if(current_state == WP_IDLE) {
//Clear the old view-list before receiving the new one //Clear the old view-list before receiving the new one
while(waypointsViewOnly.size()>0) { while(waypointsViewOnly.size()>0) {
delete waypointsViewOnly.back(); Waypoint *t = waypointsViewOnly[0];
waypointsViewOnly.pop_back(); 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 //Clear the old edit-list before receiving the new one
if (read_to_edit == true){ if (read_to_edit == true){
while(waypointsEditable.size()>0) { while(waypointsEditable.size()>0) {
delete waypointsEditable.back(); Waypoint *t = waypointsEditable[0];
waypointsEditable.pop_back(); waypointsEditable.remove(0);
delete t;
} }
emit waypointEditableListChanged();
} }
*/
protocol_timer.start(PROTOCOL_TIMEOUT_MS); protocol_timer.start(PROTOCOL_TIMEOUT_MS);
current_retries = PROTOCOL_MAX_RETRIES; current_retries = PROTOCOL_MAX_RETRIES;
......
...@@ -20,10 +20,12 @@ ...@@ -20,10 +20,12 @@
#include "WaypointEditableView.h" #include "WaypointEditableView.h"
#include "ui_WaypointEditableView.h" #include "ui_WaypointEditableView.h"
#include "ui_QGCCustomWaypointAction.h" #include "ui_QGCCustomWaypointAction.h"
#include "ui_QGCMissionDoWidget.h"
WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
QWidget(parent), QWidget(parent),
customCommand(new Ui_QGCCustomWaypointAction), customCommand(new Ui_QGCCustomWaypointAction),
doCommand(new Ui_QGCMissionDoWidget),
viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV), viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV),
m_ui(new Ui::WaypointEditableView) m_ui(new Ui::WaypointEditableView)
{ {
...@@ -34,6 +36,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -34,6 +36,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
// CUSTOM COMMAND WIDGET // CUSTOM COMMAND WIDGET
customCommand->setupUi(m_ui->customActionWidget); customCommand->setupUi(m_ui->customActionWidget);
// DO COMMAND WIDGET
//doCommand->setupUi(m_ui->customActionWidget);
// add actions // add actions
m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT); m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT);
...@@ -43,7 +48,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -43,7 +48,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("NAV: Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS); m_ui->comboBox_action->addItem(tr("NAV: Loiter Turns"),MAV_CMD_NAV_LOITER_TURNS);
m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH); m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND); m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND);
// m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET); //m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
//m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY); //m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
//m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW); //m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
//m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP); //m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
...@@ -143,6 +148,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -143,6 +148,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide(); m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 82); m_ui->horizontalLayout->insertStretch(17, 82);
m_ui->takeOffAngleSpinBox->show(); m_ui->takeOffAngleSpinBox->show();
break; break;
...@@ -155,6 +162,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -155,6 +162,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide(); m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 26); m_ui->horizontalLayout->insertStretch(17, 26);
break; break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
...@@ -166,6 +175,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -166,6 +175,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide(); m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 26); m_ui->horizontalLayout->insertStretch(17, 26);
break; break;
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
...@@ -174,6 +185,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -174,6 +185,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->turnsSpinBox->hide(); m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->show(); m_ui->holdTimeSpinBox->show();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 1); m_ui->horizontalLayout->insertStretch(17, 1);
m_ui->autoContinue->show(); m_ui->autoContinue->show();
...@@ -188,6 +201,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -188,6 +201,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide(); m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 25); m_ui->horizontalLayout->insertStretch(17, 25);
m_ui->orbitSpinBox->show(); m_ui->orbitSpinBox->show();
break; break;
...@@ -198,6 +213,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -198,6 +213,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->holdTimeSpinBox->hide(); m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 20); m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show(); m_ui->orbitSpinBox->show();
m_ui->turnsSpinBox->show(); m_ui->turnsSpinBox->show();
...@@ -209,6 +226,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -209,6 +226,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide(); m_ui->autoContinue->hide();
m_ui->acceptanceSpinBox->hide(); m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
m_ui->horizontalLayout->insertStretch(17, 20); m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show(); m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show(); m_ui->holdTimeSpinBox->show();
...@@ -219,7 +238,8 @@ void WaypointEditableView::updateActionView(int action) ...@@ -219,7 +238,8 @@ void WaypointEditableView::updateActionView(int action)
// m_ui->turnsSpinBox->hide(); // m_ui->turnsSpinBox->hide();
// m_ui->holdTimeSpinBox->show(); // m_ui->holdTimeSpinBox->show();
// m_ui->customActionWidget->hide(); // m_ui->customActionWidget->hide();
// m_ui->missionDoWidgetSlot->hide();
// m_ui->missionConditionWidgetSlot->hide();
// m_ui->autoContinue->show(); // m_ui->autoContinue->show();
// m_ui->acceptanceSpinBox->hide(); // m_ui->acceptanceSpinBox->hide();
// m_ui->yawSpinBox->hide(); // m_ui->yawSpinBox->hide();
...@@ -260,6 +280,11 @@ void WaypointEditableView::changedAction(int index) ...@@ -260,6 +280,11 @@ void WaypointEditableView::changedAction(int index)
// Update view // Update view
updateActionView(actionIndex); updateActionView(actionIndex);
break; break;
case MAV_CMD_DO_JUMP:
{
changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DO);
break;
}
case MAV_CMD_ENUM_END: case MAV_CMD_ENUM_END:
default: default:
// Switch to mission frame // Switch to mission frame
...@@ -276,9 +301,32 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode) ...@@ -276,9 +301,32 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
case QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION: case QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION:
// Hide everything, show condition widget // Hide everything, show condition widget
// TODO // TODO
break;
case QGC_WAYPOINTEDITABLEVIEW_MODE_DO: 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; break;
}
case QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING: case QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING:
// Hide almost everything // Hide almost everything
m_ui->orbitSpinBox->hide(); m_ui->orbitSpinBox->hide();
...@@ -325,6 +373,8 @@ void WaypointEditableView::updateFrameView(int frame) ...@@ -325,6 +373,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame // Coordinate frame
m_ui->comboBox_frame->show(); m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
} }
else // do not hide customActionWidget if Command is set to "Other" else // do not hide customActionWidget if Command is set to "Other"
{ {
...@@ -343,6 +393,8 @@ void WaypointEditableView::updateFrameView(int frame) ...@@ -343,6 +393,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame // Coordinate frame
m_ui->comboBox_frame->show(); m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide(); m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
} }
else // do not hide customActionWidget if Command is set to "Other" else // do not hide customActionWidget if Command is set to "Other"
{ {
......
...@@ -49,7 +49,7 @@ namespace Ui ...@@ -49,7 +49,7 @@ namespace Ui
class WaypointEditableView; class WaypointEditableView;
} }
class Ui_QGCCustomWaypointAction; class Ui_QGCCustomWaypointAction;
class Ui_QGCMissionDoWidget;
class WaypointEditableView : public QWidget class WaypointEditableView : public QWidget
{ {
Q_OBJECT Q_OBJECT
...@@ -84,6 +84,7 @@ protected: ...@@ -84,6 +84,7 @@ protected:
// Special widgets extendending the // Special widgets extendending the
// waypoint view to mission capabilities // waypoint view to mission capabilities
Ui_QGCCustomWaypointAction* customCommand; Ui_QGCCustomWaypointAction* customCommand;
Ui_QGCMissionDoWidget* doCommand;
QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
private: private:
......
...@@ -7,7 +7,7 @@ ...@@ -7,7 +7,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>2208</width> <width>2208</width>
<height>39</height> <height>37</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy"> <property name="sizePolicy">
...@@ -96,7 +96,7 @@ QPushButton:pressed { ...@@ -96,7 +96,7 @@ QPushButton:pressed {
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="5,5,5,5,50,50,50,50,50,50,5,20,20,5,10,10,10,20,5,5,5,5"> <layout class="QHBoxLayout" name="horizontalLayout" stretch="5,5,5,5,50,50,50,50,50,50,5,20,20,5,10,10,0,0,0,20,5,5,5,5">
<property name="spacing"> <property name="spacing">
<number>2</number> <number>2</number>
</property> </property>
...@@ -121,10 +121,10 @@ QPushButton:pressed { ...@@ -121,10 +121,10 @@ QPushButton:pressed {
<enum>Qt::TabFocus</enum> <enum>Qt::TabFocus</enum>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Currently selected waypoint</string> <string>Mission Start</string>
</property> </property>
<property name="statusTip"> <property name="statusTip">
<string>Currently selected waypoint</string> <string>Mission Start</string>
</property> </property>
<property name="text"> <property name="text">
<string/> <string/>
...@@ -465,16 +465,16 @@ QPushButton:pressed { ...@@ -465,16 +465,16 @@ QPushButton:pressed {
<enum>Qt::StrongFocus</enum> <enum>Qt::StrongFocus</enum>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Loiter radius</string> <string>Loiter radius. Negative for counter-clockwise</string>
</property> </property>
<property name="statusTip"> <property name="statusTip">
<string>Loiter radius</string> <string>Loiter radius. Negative for counter-clockwise</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string> m</string> <string> m</string>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>0.050000000000000</double> <double>-5000.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>5000.000000000000000</double> <double>5000.000000000000000</double>
...@@ -519,11 +519,10 @@ where to accept this waypoint as reached</string> ...@@ -519,11 +519,10 @@ where to accept this waypoint as reached</string>
</sizepolicy> </sizepolicy>
</property> </property>
<property name="toolTip"> <property name="toolTip">
<string>Rotaty wing and ground vehicles only: <string>Time to stay/loiter at this position before advancing</string>
Time to stay at this position before advancing</string>
</property> </property>
<property name="statusTip"> <property name="statusTip">
<string>Rotaty wing and ground vehicles only: Time to stay at this position before advancing</string> <string>Time to stay/loiter at this position before advancing</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string> s</string> <string> s</string>
...@@ -595,7 +594,33 @@ Time to stay at this position before advancing</string> ...@@ -595,7 +594,33 @@ Time to stay at this position before advancing</string>
<item> <item>
<widget class="QWidget" name="customActionWidget" native="true"> <widget class="QWidget" name="customActionWidget" native="true">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QWidget" name="missionDoWidgetSlot" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<widget class="QWidget" name="missionConditionWidgetSlot" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
......
...@@ -21,59 +21,56 @@ void WaypointViewOnlyView::changedAutoContinue(int state) ...@@ -21,59 +21,56 @@ void WaypointViewOnlyView::changedAutoContinue(int state)
{ {
new_value = true; 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); emit changeAutoContinue(wp->getId(),new_value);
} }
void WaypointViewOnlyView::changedCurrent(int state) 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(); qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
m_ui->current->blockSignals(true); m_ui->current->blockSignals(true);
if (state == 0)
{
/*
m_ui->current->setStyleSheet("");
*/ if (m_ui->current->isChecked() == false)
if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current {
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); 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); m_ui->current->setCheckState(Qt::Unchecked);
wp->setCurrent(false); qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Unchecked false. set false " << m_ui->current->isChecked();
} }
} }
else else
{ {
/* hightlightDesiredCurrent(true);
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->setCheckState(Qt::Unchecked);
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Checked new. Sending set_current request to Manager " << m_ui->current->isChecked();
m_ui->current->setStyleSheet("*::indicator { \
border: 1px solid #777777; \
border-radius: 2px; \
color: #999999; \
width: 10px; \
height: 10px; \
}");
*/
wp->setCurrent(true);
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
} }
m_ui->current->blockSignals(false); m_ui->current->blockSignals(false);
} }
void WaypointViewOnlyView::setCurrent(bool state) 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->blockSignals(true);
m_ui->current->setChecked(state); 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); m_ui->current->blockSignals(false);
} }
...@@ -159,8 +156,7 @@ void WaypointViewOnlyView::updateValues() ...@@ -159,8 +156,7 @@ void WaypointViewOnlyView::updateValues()
} }
} }
hightlightDesiredCurrent(wp->getCurrent());
if (m_ui->current->isChecked() != wp->getCurrent()) if (m_ui->current->isChecked() != wp->getCurrent())
{ {
m_ui->current->blockSignals(true); m_ui->current->blockSignals(true);
...@@ -209,6 +205,110 @@ void WaypointViewOnlyView::updateValues() ...@@ -209,6 +205,110 @@ void WaypointViewOnlyView::updateValues()
} //end Frame switch } //end Frame switch
break; break;
} }
case MAV_CMD_NAV_LOITER_UNLIM:
{
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there indefinitely (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()));
}
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there indefinitely (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there indefinitely (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()));
}
break;
}
} //end Frame switch
break;
}
case MAV_CMD_NAV_LOITER_TURNS:
{
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there for %5 turns (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there for %5 turns (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there for %5 turns (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
} //end Frame switch
break;
}
case MAV_CMD_NAV_LOITER_TIME:
{
switch (wp->getFrame())
{
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there for %5s (clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(</b>lat <b>%1<sup>o</sup></b>, lon <b>%2<sup>o</sup></b>, alt <b>%3)</b> and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 7).arg(wp->getY(),0, 'f', 7).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
case MAV_FRAME_LOCAL_NED:
default:
{
if (wp->getParam3()>=0)
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there for %5s (clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f',2).arg(wp->getParam3()).arg(wp->getParam1()));
}
else
{
m_ui->displayBar->setText(QString("Go to <b>(%1, %2, %3)</b> and loiter there for %5s (counter-clockwise); rad: %4").arg(wp->getX(),0, 'f', 2).arg(wp->getY(),0, 'f', 2).arg(wp->getZ(),0, 'f', 2).arg(-wp->getParam3()).arg(wp->getParam1()));
}
break;
}
} //end Frame switch
break;
}
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
{
m_ui->displayBar->setText(QString("Return to launch location"));
break;
}
case MAV_CMD_NAV_LAND: case MAV_CMD_NAV_LAND:
{ {
switch (wp->getFrame()) switch (wp->getFrame())
...@@ -302,6 +402,30 @@ void WaypointViewOnlyView::updateValues() ...@@ -302,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() WaypointViewOnlyView::~WaypointViewOnlyView()
{ {
delete m_ui; delete m_ui;
......
...@@ -31,6 +31,7 @@ protected: ...@@ -31,6 +31,7 @@ protected:
Waypoint* wp; Waypoint* wp;
private: private:
void hightlightDesiredCurrent(bool hightlight_on);
Ui::WaypointViewOnlyView *m_ui; Ui::WaypointViewOnlyView *m_ui;
}; };
......
This diff is collapsed.
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