Commit 16092c24 authored by pixhawk's avatar pixhawk

Refactoring WP interface, somewhat brittle and untested at this point - use...

Refactoring WP interface, somewhat brittle and untested at this point - use the master branch if you need stable code right now
parent 70b09fc5
......@@ -206,18 +206,36 @@ void Waypoint::setParam2(double param2)
void Waypoint::setParam3(double param3)
{
if (this->x != param3)
if (this->orbit != param3)
{
this->x = param3;
this->orbit = param3;
emit changed(this);
}
}
void Waypoint::setParam4(double param4)
{
if (this->y != param4)
if (this->x != param4)
{
this->y = param4;
this->x = param4;
emit changed(this);
}
}
void Waypoint::setParam5(double param5)
{
if (this->y != param5)
{
this->y = param5;
emit changed(this);
}
}
void Waypoint::setParam6(double param6)
{
if (this->z != param6)
{
this->z = param6;
emit changed(this);
}
}
......
......@@ -60,8 +60,10 @@ public:
double getHoldTime() const { return param2; }
double getParam1() const { return param1; }
double getParam2() const { return param2; }
double getParam3() const { return x; }
double getParam4() const { return y; }
double getParam3() const { return orbit; }
double getParam4() const { return x; }
double getParam5() const { return y; }
double getParam6() const { return z; }
int getTurns() const { return param1; }
MAV_FRAME getFrame() const { return frame; }
MAV_ACTION getAction() const { return action; }
......@@ -105,6 +107,8 @@ public slots:
void setParam2(double param2);
void setParam3(double param3);
void setParam4(double param4);
void setParam5(double param5);
void setParam6(double param6);
void setAcceptanceRadius(double radius);
void setHoldTime(int holdTime);
/** @brief Number of turns for loiter waypoints */
......
......@@ -82,6 +82,10 @@ void MAVLinkProtocol::loadSettings()
{
m_logfile = new QFile(settings.value("LOGFILE_NAME").toString());
}
else if (m_logfile == NULL)
{
m_logfile = new QFile(QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink");
}
// Enable logging
enableLogging(settings.value("LOGGING_ENABLED", m_loggingEnabled).toBool());
......@@ -143,7 +147,7 @@ QString MAVLinkProtocol::getLogfileName()
}
else
{
return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgrouncontrol_packetlog.mavlink";
return QDesktopServices::storageLocation(QDesktopServices::HomeLocation) + "/qgroundcontrol_packetlog.mavlink";
}
}
......
......@@ -129,8 +129,8 @@ void WaypointList::setUAS(UASInterface* uas)
connect(uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(uas->getWaypointManager(), SIGNAL(waypointChanged(int,Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)));
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
//connect(uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
//connect(uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
......@@ -148,11 +148,9 @@ void WaypointList::loadWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager()->loadWaypoints(fileName);
}
}
}
void WaypointList::transmit()
......
......@@ -103,6 +103,8 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(customCommand->param2SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam2(double)));
connect(customCommand->param3SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam3(double)));
connect(customCommand->param4SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam4(double)));
connect(customCommand->param5SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam5(double)));
connect(customCommand->param6SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam6(double)));
// MISSION ELEMENT WIDGET
// TODO
......@@ -126,7 +128,7 @@ void WaypointView::moveDown()
void WaypointView::remove()
{
emit removeWaypoint(wp);
delete this;
deleteLater();
}
void WaypointView::changedAutoContinue(int state)
......@@ -473,8 +475,6 @@ void WaypointView::updateValues()
// UPDATE CUSTOM ACTION WIDGET
qDebug() << "UPDATING CUSTOM ACTION WIDGET";
if (customCommand->commandSpinBox->value() != wp->getAction())
{
customCommand->commandSpinBox->setValue(wp->getAction());
......@@ -500,6 +500,16 @@ void WaypointView::updateValues()
{
customCommand->param4SpinBox->setValue(wp->getParam4());
}
// Param 5
if (customCommand->param5SpinBox->value() != wp->getParam5())
{
customCommand->param5SpinBox->setValue(wp->getParam5());
}
// Param 6
if (customCommand->param6SpinBox->value() != wp->getParam6())
{
customCommand->param6SpinBox->setValue(wp->getParam6());
}
wp->blockSignals(false);
}
......
......@@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>791</width>
<width>1105</width>
<height>25</height>
</rect>
</property>
......@@ -102,7 +102,7 @@
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="doubleSpinBox">
<widget class="QDoubleSpinBox" name="param6SpinBox">
<property name="prefix">
<string>Z/P6 </string>
</property>
......
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