Browse Source

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol

QGC4.4
lm 15 years ago
parent
commit
0566491ba5
  1. 33
      src/Waypoint.cc
  2. 9
      src/Waypoint.h
  3. 5
      src/uas/UASWaypointManager.cc
  4. 2
      src/uas/UASWaypointManager.h
  5. 2
      src/ui/HSIDisplay.cc
  6. 16
      src/ui/WaypointList.cc
  7. 2
      src/ui/WaypointList.h
  8. 7
      src/ui/WaypointView.cc
  9. 61
      src/ui/WaypointView.ui

33
src/Waypoint.cc

@ -32,15 +32,17 @@ This file is part of the PIXHAWK project
#include "Waypoint.h" #include "Waypoint.h"
Waypoint::Waypoint(quint16 id, float x, float y, float z, float yaw, bool autocontinue, bool current) Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _autocontinue, bool _current, float _orbit, int _holdTime)
: id(_id),
x(_x),
y(_y),
z(_z),
yaw(_yaw),
autocontinue(_autocontinue),
current(_current),
orbit(_orbit),
holdTime(_holdTime)
{ {
this->id = id;
this->x = x;
this->y = y;
this->z = z;
this->yaw = yaw;
this->autocontinue = autocontinue;
this->current = current;
} }
Waypoint::~Waypoint() Waypoint::~Waypoint()
@ -83,6 +85,16 @@ void Waypoint::setCurrent(bool current)
this->current = current; this->current = current;
} }
void Waypoint::setOrbit(float orbit)
{
this->orbit = orbit;
}
void Waypoint::setHoldTime(int holdTime)
{
this->holdTime = holdTime;
}
void Waypoint::setX(double x) void Waypoint::setX(double x)
{ {
this->x = x; this->x = x;
@ -102,3 +114,8 @@ void Waypoint::setYaw(double yaw)
{ {
this->yaw = yaw; this->yaw = yaw;
} }
void Waypoint::setOrbit(double orbit)
{
this->orbit = orbit;
}

9
src/Waypoint.h

@ -41,7 +41,7 @@ class Waypoint : public QObject
Q_OBJECT Q_OBJECT
public: public:
Waypoint(quint16 id = 0, float x = 0.0f, float y = 0.0f, float z = 0.0f, float yaw = 0.0f, bool autocontinue = false, bool current = false); Waypoint(quint16 id = 0, float x = 0.0f, float y = 0.0f, float z = 0.0f, float yaw = 0.0f, bool autocontinue = false, bool current = false, float orbit = 0.1f, int holdTime = 2000);
~Waypoint(); ~Waypoint();
quint16 getId() const { return id; } quint16 getId() const { return id; }
@ -51,6 +51,8 @@ public:
float getYaw() const { return yaw; } float getYaw() const { return yaw; }
bool getAutoContinue() const { return autocontinue; } bool getAutoContinue() const { return autocontinue; }
bool getCurrent() const { return current; } bool getCurrent() const { return current; }
float getOrbit() const { return orbit; }
float getHoldTime() const { return holdTime; }
private: private:
quint16 id; quint16 id;
@ -60,6 +62,8 @@ private:
float yaw; float yaw;
bool autocontinue; bool autocontinue;
bool current; bool current;
float orbit;
int holdTime;
public slots: public slots:
void setId(quint16 id); void setId(quint16 id);
@ -69,12 +73,15 @@ public slots:
void setYaw(float yaw); void setYaw(float yaw);
void setAutocontinue(bool autoContinue); void setAutocontinue(bool autoContinue);
void setCurrent(bool current); void setCurrent(bool current);
void setOrbit(float orbit);
void setHoldTime(int holdTime);
//for QDoubleSpin //for QDoubleSpin
void setX(double x); void setX(double x);
void setY(double y); void setY(double y);
void setZ(double z); void setZ(double z);
void setYaw(double yaw); void setYaw(double yaw);
void setOrbit(double orbit);
}; };
#endif // WAYPOINT_H #endif // WAYPOINT_H

5
src/uas/UASWaypointManager.cc

@ -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)
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();

2
src/uas/UASWaypointManager.h

@ -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

2
src/ui/HSIDisplay.cc

@ -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;

16
src/ui/WaypointList.cc

@ -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)
} }
} }
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()
{ {
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()
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()
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();
} }

2
src/ui/WaypointList.h

@ -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);

7
src/ui/WaypointView.cc

@ -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) :
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)

61
src/ui/WaypointView.ui

@ -6,7 +6,7 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>595</width> <width>763</width>
<height>40</height> <height>40</height>
</rect> </rect>
</property> </property>
@ -155,7 +155,7 @@ QProgressBar::chunk#thrustBar {
<property name="title"> <property name="title">
<string/> <string/>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="0,0,5,0,0,0,0,0,0,0,0"> <layout class="QHBoxLayout" name="horizontalLayout" stretch="0,0,0,0,0,0,0,0,0,0,0,0,0">
<property name="spacing"> <property name="spacing">
<number>2</number> <number>2</number>
</property> </property>
@ -216,13 +216,13 @@ QProgressBar::chunk#thrustBar {
<string>Position X coordinate</string> <string>Position X coordinate</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string>m</string> <string> m</string>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>-100000.000000000000000</double> <double>-1000.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>100000.000000000000000</double> <double>1000.000000000000000</double>
</property> </property>
<property name="singleStep"> <property name="singleStep">
<double>0.050000000000000</double> <double>0.050000000000000</double>
@ -235,13 +235,13 @@ QProgressBar::chunk#thrustBar {
<string>Position Y coordinate</string> <string>Position Y coordinate</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string>m</string> <string> m</string>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>-100000.000000000000000</double> <double>-1000.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>100000.000000000000000</double> <double>1000.000000000000000</double>
</property> </property>
<property name="singleStep"> <property name="singleStep">
<double>0.050000000000000</double> <double>0.050000000000000</double>
@ -257,10 +257,10 @@ QProgressBar::chunk#thrustBar {
<string>Position Z coordinate</string> <string>Position Z coordinate</string>
</property> </property>
<property name="suffix"> <property name="suffix">
<string>m</string> <string> m</string>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>-100000.000000000000000</double> <double>-1000.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>0.000000000000000</double> <double>0.000000000000000</double>
@ -284,6 +284,47 @@ QProgressBar::chunk#thrustBar {
<property name="maximum"> <property name="maximum">
<number>359</number> <number>359</number>
</property> </property>
<property name="singleStep">
<number>10</number>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="orbitSpinBox">
<property name="toolTip">
<string>Orbit radius</string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>0.050000000000000</double>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="holdTimeSpinBox">
<property name="statusTip">
<string>Time in milliseconds that the MAV has to stay inside the orbit before advancing</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>500</number>
</property>
<property name="value">
<number>0</number>
</property>
</widget> </widget>
</item> </item>
<item> <item>

Loading…
Cancel
Save