Commit b862021a authored by lm's avatar lm

Decoupled WP frame from custom command fields

parent d05c3516
......@@ -455,7 +455,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "altitude", "m", hud.alt, time);
emit valueChanged(uasId, "heading", "deg", hud.heading, time);
emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
emit valueChanged(uasId, "throttle", "m/s", hud.throttle, time);
emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
emit thrustChanged(this, hud.throttle/100.0);
emit altitudeChanged(uasId, hud.alt);
//yaw = (hud.heading-180.0f/360.0f)*M_PI;
......
......@@ -408,7 +408,7 @@ void MainWindow::buildPxWidgets()
acceptList->append("0,airspeed,m/s,30");
acceptList->append("0,groundspeed,m/s,30");
acceptList->append("0,climbrate,m/s,30");
acceptList->append("0,throttle,m/s,100");
acceptList->append("0,throttle,%,100");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
......
......@@ -24,6 +24,7 @@
WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
QWidget(parent),
customCommand(new Ui_QGCCustomWaypointAction),
viewMode(QGC_WAYPOINTVIEW_MODE_NAV),
m_ui(new Ui::WaypointView)
{
m_ui->setupUi(this);
......@@ -247,47 +248,28 @@ void WaypointView::changedAction(int index)
case MAV_CMD_NAV_LOITER_TIME:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_DO_SET_MODE:
// Back to global frame
if (wp->getFrame() == MAV_FRAME_MISSION) changedFrame(0);
changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV);
// Update frame view
updateFrameView(m_ui->comboBox_frame->currentIndex());
// Update view
updateActionView(actionIndex);
break;
case MAV_CMD_ENUM_END:
default:
// Switch to mission frame
changedFrame(MAV_FRAME_MISSION);
wp->setFrame(MAV_FRAME_MISSION);
changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING);
break;
}
}
void WaypointView::updateFrameView(int frame)
void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
{
switch(frame)
switch (mode)
{
case MAV_FRAME_GLOBAL:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_LOCAL:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
case QGC_WAYPOINTVIEW_MODE_NAV:
break;
case MAV_FRAME_MISSION:
case QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING:
// Hide almost everything
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
......@@ -301,7 +283,6 @@ void WaypointView::updateFrameView(int frame)
m_ui->latSpinBox->hide();
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->comboBox_frame->hide();
// Show action widget
if (!m_ui->customActionWidget->isVisible())
......@@ -313,6 +294,35 @@ void WaypointView::updateFrameView(int frame)
m_ui->autoContinue->show();
}
break;
}
}
void WaypointView::updateFrameView(int frame)
{
switch(frame)
{
case MAV_FRAME_GLOBAL:
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
case MAV_FRAME_LOCAL:
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
break;
default:
std::cerr << "unknown frame" << std::endl;
}
......@@ -403,10 +413,8 @@ void WaypointView::updateValues()
}
}
break;
case (MAV_FRAME_MISSION):
{
// TODO Change to mission view
}
default:
// Do nothing
break;
}
......
......@@ -37,6 +37,13 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <iostream>
enum QGC_WAYPOINTVIEW_MODE {
QGC_WAYPOINTVIEW_MODE_NAV,
QGC_WAYPOINTVIEW_MODE_CONDITION,
QGC_WAYPOINTVIEW_MODE_DO,
QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING
};
namespace Ui {
class WaypointView;
}
......@@ -68,12 +75,16 @@ public slots:
void setYaw(int); //hidden degree to radian conversion
protected slots:
void changeViewMode(QGC_WAYPOINTVIEW_MODE mode);
protected:
virtual void changeEvent(QEvent *e);
Waypoint* wp;
// Special widgets extendending the
// waypoint view to mission capabilities
Ui_QGCCustomWaypointAction* customCommand;
QGC_WAYPOINTVIEW_MODE viewMode;
private:
Ui::WaypointView *m_ui;
......
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