Commit c3c390c2 authored by pixhawk's avatar pixhawk

new waypoint fields included

parent 04f32749
...@@ -94,7 +94,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ ...@@ -94,7 +94,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id) if(wp->seq == current_wp_id)
{ {
//update the UI FIXME //update the UI FIXME
emit waypointUpdated(uas.getUASID(), wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current); emit waypointUpdated(uas.getUASID(), wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->orbit, wp->hold_time);
//get next waypoint //get next waypoint
current_wp_id++; current_wp_id++;
...@@ -237,7 +237,8 @@ void UASWaypointManager::sendWaypoints(const QVector<Waypoint*> &list) ...@@ -237,7 +237,8 @@ void UASWaypointManager::sendWaypoints(const QVector<Waypoint*> &list)
cur_d->autocontinue = cur_s->getAutoContinue(); cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent(); cur_d->current = cur_s->getCurrent();
cur_d->orbit = 0.1f; //FIXME cur_d->orbit = cur_s->getOrbit();
cur_d->hold_time = cur_s->getHoldTime();
cur_d->type = 1; //FIXME cur_d->type = 1; //FIXME
cur_d->seq = i; cur_d->seq = i;
cur_d->x = cur_s->getX(); cur_d->x = cur_s->getX();
......
...@@ -71,7 +71,7 @@ public slots: ...@@ -71,7 +71,7 @@ public slots:
void sendWaypoints(const QVector<Waypoint *> &list); void sendWaypoints(const QVector<Waypoint *> &list);
signals: signals:
void waypointUpdated(int,quint16,double,double,double,double,bool,bool); ///< Adds a waypoint to the waypoint list widget void waypointUpdated(int,quint16,double,double,double,double,bool,bool,double,int); ///< Adds a waypoint to the waypoint list widget
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string void updateStatusString(const QString &); ///< emits the current status string
......
...@@ -450,7 +450,7 @@ void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesir ...@@ -450,7 +450,7 @@ void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesir
bodyYawSet = yawDesired; bodyYawSet = yawDesired;
mavInitialized = true; mavInitialized = true;
qDebug() << "Received setpoint at x: " << x << "metric y:" << y; // qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
// posXSet = xDesired; // posXSet = xDesired;
// posYSet = yDesired; // posYSet = yDesired;
// posZSet = zDesired; // posZSet = zDesired;
......
...@@ -96,7 +96,7 @@ void WaypointList::setUAS(UASInterface* uas) ...@@ -96,7 +96,7 @@ void WaypointList::setUAS(UASInterface* uas)
this->uas = uas; this->uas = uas;
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &))); connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(&uas->getWaypointManager(), SIGNAL(waypointUpdated(int,quint16,double,double,double,double,bool,bool)), this, SLOT(setWaypoint(int,quint16,double,double,double,double,bool,bool))); connect(&uas->getWaypointManager(), SIGNAL(waypointUpdated(int,quint16,double,double,double,double,bool,bool,double,int)), this, SLOT(setWaypoint(int,quint16,double,double,double,double,bool,bool,double,int)));
connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(this, SIGNAL(sendWaypoints(const QVector<Waypoint*> &)), &uas->getWaypointManager(), SLOT(sendWaypoints(const QVector<Waypoint*> &))); connect(this, SIGNAL(sendWaypoints(const QVector<Waypoint*> &)), &uas->getWaypointManager(), SLOT(sendWaypoints(const QVector<Waypoint*> &)));
...@@ -105,11 +105,11 @@ void WaypointList::setUAS(UASInterface* uas) ...@@ -105,11 +105,11 @@ void WaypointList::setUAS(UASInterface* uas)
} }
} }
void WaypointList::setWaypoint(int uasId, quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current) void WaypointList::setWaypoint(int uasId, quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime)
{ {
if (uasId == this->uas->getUASID()) if (uasId == this->uas->getUASID())
{ {
Waypoint* wp = new Waypoint(id, x, y, z, yaw, autocontinue, current); Waypoint* wp = new Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime);
addWaypoint(wp); addWaypoint(wp);
} }
} }
...@@ -168,11 +168,11 @@ void WaypointList::add() ...@@ -168,11 +168,11 @@ void WaypointList::add()
{ {
if (waypoints.size() > 0) if (waypoints.size() > 0)
{ {
addWaypoint(new Waypoint(waypoints.size(), 1.1, 1.1, -0.6, 0.0, true, false)); addWaypoint(new Waypoint(waypoints.size(), 1.1, 1.1, -0.6, 0.0, true, false, 0.1, 2000));
} }
else else
{ {
addWaypoint(new Waypoint(waypoints.size(), 0.0, 0.0, -0.0, 0.0, true, true)); addWaypoint(new Waypoint(waypoints.size(), 1.1, 1.1, -0.6, 0.0, true, true, 0.1, 2000));
} }
} }
} }
...@@ -302,7 +302,7 @@ void WaypointList::saveWaypoints() ...@@ -302,7 +302,7 @@ void WaypointList::saveWaypoints()
for (int i = 0; i < waypoints.size(); i++) for (int i = 0; i < waypoints.size(); i++)
{ {
Waypoint* wp = waypoints[i]; Waypoint* wp = waypoints[i];
in << "~" << wp->getId() << "~" << wp->getX() << "~" << wp->getY() << "~" << wp->getZ() << "~" << wp->getYaw() << "~" << wp->getAutoContinue() << "~" << wp->getCurrent() << "\n"; in << "\t" << wp->getId() << "\t" << wp->getX() << "\t" << wp->getY() << "\t" << wp->getZ() << "\t" << wp->getYaw() << "\t" << wp->getAutoContinue() << "\t" << wp->getCurrent() << wp->getOrbit() << "\t" << wp->getHoldTime() << "\n";
in.flush(); in.flush();
} }
file.close(); file.close();
...@@ -323,9 +323,9 @@ void WaypointList::loadWaypoints() ...@@ -323,9 +323,9 @@ void WaypointList::loadWaypoints()
QTextStream in(&file); QTextStream in(&file);
while (!in.atEnd()) while (!in.atEnd())
{ {
QStringList wpParams = in.readLine().split("~"); QStringList wpParams = in.readLine().split("\t");
if (wpParams.size() == 8) if (wpParams.size() == 8)
addWaypoint(new Waypoint(wpParams[1].toInt(), wpParams[2].toDouble(), wpParams[3].toDouble(), wpParams[4].toDouble(), wpParams[5].toDouble(), (wpParams[6].toInt() == 1 ? true : false), (wpParams[7].toInt() == 1 ? true : false))); addWaypoint(new Waypoint(wpParams[1].toInt(), wpParams[2].toDouble(), wpParams[3].toDouble(), wpParams[4].toDouble(), wpParams[5].toDouble(), (wpParams[6].toInt() == 1 ? true : false), (wpParams[7].toInt() == 1 ? true : false), wpParams[8].toDouble(), wpParams[9].toInt()));
} }
file.close(); file.close();
} }
......
...@@ -72,7 +72,7 @@ public slots: ...@@ -72,7 +72,7 @@ public slots:
void currentWaypointChanged(quint16 seq); void currentWaypointChanged(quint16 seq);
//To be moved to UASWaypointManager (?) //To be moved to UASWaypointManager (?)
void setWaypoint(int uasId, quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current); void setWaypoint(int uasId, quint16 id, double x, double y, double z, double yaw, bool autocontinue, bool current, double orbit, int holdTime);
void addWaypoint(Waypoint* wp); void addWaypoint(Waypoint* wp);
void removeWaypoint(Waypoint* wp); void removeWaypoint(Waypoint* wp);
void waypointReached(UASInterface* uas, quint16 waypointId); void waypointReached(UASInterface* uas, quint16 waypointId);
......
...@@ -54,7 +54,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : ...@@ -54,7 +54,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.); m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->selectedBox->setChecked(wp->getCurrent()); m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue()); m_ui->autoContinue->setChecked(wp->getAutoContinue());
m_ui->idLabel->setText(QString("%1").arg(wp->getId())); m_ui->idLabel->setText(QString("%1").arg(wp->getId()));\
m_ui->orbitSpinBox->setValue(wp->getOrbit());
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double))); connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double))); connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
...@@ -70,6 +72,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : ...@@ -70,6 +72,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int))); connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int)));
connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int))); connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
connect(m_ui->orbitSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
} }
void WaypointView::setYaw(int yawDegree) void WaypointView::setYaw(int yawDegree)
......
...@@ -323,7 +323,7 @@ QProgressBar::chunk#thrustBar { ...@@ -323,7 +323,7 @@ QProgressBar::chunk#thrustBar {
<number>500</number> <number>500</number>
</property> </property>
<property name="value"> <property name="value">
<number>2000</number> <number>0</number>
</property> </property>
</widget> </widget>
</item> </item>
......
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