Commit 3bf94a1e authored by pixhawk's avatar pixhawk

worked on waypoints, removed waypoint names

parent ea2ee6c1
......@@ -3,9 +3,9 @@
# from http://github.com/pixhawk/qmapcontrol/
# over bundled version in lib directory
# Version from GIT repository is preferred
include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
#include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary
#include(lib/QMapControl/QMapControl.pri)
include(lib/QMapControl/QMapControl.pri)
#message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")
......
......@@ -26,29 +26,21 @@ This file is part of the PIXHAWK project
* @brief Waypoint class
*
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include "Waypoint.h"
Waypoint::Waypoint(QString name, int id, double x, double y, double z, double yaw, bool autocontinue, bool current)
Waypoint::Waypoint(quint16 id, float x, float y, float z, float yaw, bool autocontinue, bool current)
{
this->id = id;
this->x = x;
this->y = y;
this->z = z;
this->yaw = yaw;
this->autocontinue = autocontinue;
this->current = current;
this->name = name;
}
int Waypoint::getId()
{
return id;
}
Waypoint::~Waypoint()
......@@ -56,27 +48,27 @@ Waypoint::~Waypoint()
}
void Waypoint::setName(QString name)
void Waypoint::setId(quint16 id)
{
this->name = name;
this->id = id;
}
void Waypoint::setX(double x)
void Waypoint::setX(float x)
{
this->x = x;
}
void Waypoint::setY(double y)
void Waypoint::setY(float y)
{
this->y = y;
}
void Waypoint::setZ(double z)
void Waypoint::setZ(float z)
{
this->z = z;
}
void Waypoint::setYaw(double yaw)
void Waypoint::setYaw(float yaw)
{
this->yaw = yaw;
}
......
......@@ -26,6 +26,7 @@ This file is part of the PIXHAWK project
* @brief Waypoint class
*
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
......@@ -38,35 +39,36 @@ This file is part of the PIXHAWK project
class Waypoint : public QObject
{
Q_OBJECT
public:
Waypoint(QString name, int id = 0, double x = 0.0f, double y = 0.0f, double z = 0.0f, double 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);
~Waypoint();
int getId();
int id;
double x;
double y;
double z;
double yaw;
quint16 getId() const { return id; }
float getX() const { return x; }
float getY() const { return y; }
float getZ() const { return z; }
float getYaw() const { return yaw; }
bool getAutoContinue() const { return autocontinue; }
bool getCurrent() const { return current; }
private:
quint16 id;
float x;
float y;
float z;
float yaw;
bool autocontinue;
bool current;
QString name;
public slots:
void setName(QString name);
void setX(double x);
void setY(double y);
void setZ(double z);
void setYaw(double yaw);
void setId(quint16 id);
void setX(float x);
void setY(float y);
void setZ(float z);
void setYaw(float yaw);
void setAutocontinue(bool autoContinue);
void setCurrent(bool current);
};
#endif // WAYPOINT_H
......@@ -15,22 +15,13 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
{
if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid)
{
qDebug() << "handleWaypointCount";
qDebug() << "got waypoint count (" << count << ") from ID " << systemId;
current_count = count;
mavlink_message_t message;
mavlink_waypoint_request_t wpr;
wpr.target_system = uas.getUASID();
wpr.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpr.seq = 0;
current_wp_id = 0;
current_state = WP_GETLIST_GETWPS;
mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr);
uas.sendMessage(message);
sendWaypointRequest(current_wp_id);
}
}
......@@ -38,7 +29,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
{
if (systemId == current_partner_systemid && compId == current_partner_compid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id)
{
qDebug() << "handleWaypoint";
qDebug() << "got waypoint (" << wp->seq << ") from ID " << systemId;
if(wp->seq == current_wp_id)
{
......@@ -50,15 +41,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(current_wp_id < current_count)
{
mavlink_message_t message;
mavlink_waypoint_request_t wpr;
wpr.target_system = uas.getUASID();
wpr.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpr.seq = current_wp_id;
mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr);
uas.sendMessage(message);
sendWaypointRequest(current_wp_id);
}
else
{
......@@ -68,6 +51,10 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
current_wp_id = 0;
current_partner_systemid = 0;
current_partner_compid = 0;
emit updateStatusString("done.");
qDebug() << "got all waypoints from from ID " << systemId;
}
}
else
......@@ -83,7 +70,7 @@ void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, m
{
qDebug() << "handleWaypointRequest";
if (wpr->seq < 0)
if (wpr->seq < waypoint_buffer.count())
{
//TODO: send waypoint
}
......@@ -113,7 +100,6 @@ void UASWaypointManager::requestWaypoints()
{
if(current_state == WP_IDLE)
{
qDebug() << "requestWaypoints";
mavlink_message_t message;
mavlink_waypoint_request_list_t wprl;
......@@ -125,27 +111,80 @@ void UASWaypointManager::requestWaypoints()
current_partner_systemid = uas.getUASID();
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
qDebug() << "sent waypoint list request to ID " << wprl.target_system;
const QString str = QString("requesting waypoint list...");
emit updateStatusString(str);
mavlink_msg_waypoint_request_list_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wprl);
uas.sendMessage(message);
uas.sendMessage(message);
}
}
void UASWaypointManager::sendWaypoints(void)
void UASWaypointManager::sendWaypoints(const QVector<Waypoint *> &list)
{
mavlink_message_t message;
mavlink_waypoint_count_t wpc;
if (current_state == WP_IDLE)
{
current_count = list.count();
current_state = WP_SENDLIST;
current_wp_id = 0;
wpc.target_system = uas.getUASID();
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = 0; //TODO
//copy waypoint data to local buffer
for (int i=0; i < current_count; i++)
{
waypoint_buffer.push_back(new mavlink_waypoint_t);
mavlink_waypoint_t *cur_d = waypoint_buffer.back();
memset(cur_d, 0, sizeof(mavlink_waypoint_t)); //initialize with zeros
const Waypoint *cur_s = list.at(i);
cur_d->autocontinue = cur_s->getAutoContinue();
cur_d->current = cur_s->getCurrent();
cur_d->seq = i;
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
cur_d->z = cur_s->getZ();
cur_d->yaw = cur_s->getYaw();
}
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
uas.sendMessage(message);
//send the waypoint count to UAS (this starts the send transaction)
mavlink_message_t message;
mavlink_waypoint_count_t wpc;
wpc.target_system = uas.getUASID();
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
const QString str = QString("start transmitting waypoints...");
emit updateStatusString(str);
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
uas.sendMessage(message);
}
else
{
//we're in another transaction, ignore command
qDebug() << "UASWaypointManager::sendWaypoints() doing something else ignoring command";
}
}
void UASWaypointManager::getWaypoint(quint16 seq)
void UASWaypointManager::sendWaypointRequest(quint16 seq)
{
mavlink_message_t message;
mavlink_waypoint_request_t wpr;
wpr.target_system = uas.getUASID();
wpr.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpr.seq = seq;
mavlink_msg_waypoint_request_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpr);
uas.sendMessage(message);
qDebug() << "sent waypoint request (" << wpr.seq << ") to ID " << wpr.target_system;
const QString str = QString("retrieving waypoint ID %1 of %2 total").arg(wpr.seq).arg(current_count);
emit updateStatusString(str);
}
void UASWaypointManager::waypointChanged(Waypoint*)
......
......@@ -2,6 +2,7 @@
#define UASWAYPOINTMANAGER_H
#include <QObject>
#include <QVector>
#include "Waypoint.h"
#include <mavlink.h>
class UAS;
......@@ -26,26 +27,29 @@ public:
void handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_waypoint_request_t *wpr);
private:
void getWaypoint(quint16 seq);
void sendWaypointRequest(quint16 seq);
public slots:
void clearWaypointList();
void currentWaypointChanged(int);
void removeWaypointId(int);
void requestWaypoints();
void sendWaypoints(void);
void sendWaypoints(const QVector<Waypoint *> &list);
void waypointChanged(Waypoint*);
signals:
void waypointUpdated(int,int,double,double,double,double,bool,bool);
void waypointUpdated(int,int,double,double,double,double,bool,bool); ///< Adds a waypoint to the waypoint list widget
void updateStatusString(const QString &); ///< updates the current status string
private:
UAS &uas;
quint16 current_wp_id; ///< The last used waypoint ID
quint16 current_count;
WaypointState current_state; ///< The current state
quint8 current_partner_systemid;
quint8 current_partner_compid;
UAS &uas; ///< Reference to the corresponding UAS
quint16 current_wp_id; ///< The last used waypoint ID in the current protocol transaction
quint16 current_count; ///< The number of waypoints in the current protocol transaction
WaypointState current_state; ///< The current protocol state
quint8 current_partner_systemid; ///< The current protocol communication target system
quint8 current_partner_compid; ///< The current protocol communication target component
QVector<mavlink_waypoint_t *> waypoint_buffer; ///< communication buffer for waypoints
};
#endif // UASWAYPOINTMANAGER_H
......@@ -27,6 +27,7 @@ This file is part of the PIXHAWK project
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
......@@ -74,6 +75,9 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
connect(transmitDelay, SIGNAL(timeout()), this, SLOT(reenableTransmit()));
// STATUS LABEL
updateStatusLabel("");
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
setUAS(uas);
}
......@@ -83,6 +87,11 @@ WaypointList::~WaypointList()
delete m_ui;
}
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::setUAS(UASInterface* uas)
{
if (this->uas == NULL && uas != NULL)
......@@ -95,10 +104,12 @@ void WaypointList::setUAS(UASInterface* uas)
connect(this, SIGNAL(requestWaypoints()), &uas->getWaypointManager(), SLOT(requestWaypoints()));
connect(this, SIGNAL(clearWaypointList()), &uas->getWaypointManager(), SLOT(clearWaypointList()));
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
// This slot is not implemented in UAS: connect(this, SIGNAL(removeWaypointId(int)), uas, SLOT(removeWaypoint(Waypoint*)));
qDebug() << "Requesting waypoints";
emit requestWaypoints();
//qDebug() << "Requesting waypoints";
//emit requestWaypoints();
}
}
......@@ -114,7 +125,7 @@ void WaypointList::setWaypoint(int uasId, int id, double x, double y, double z,
string = waypointNames.value(id);
}
Waypoint* wp = new Waypoint(string, id, x, y, z, yaw, autocontinue, current);
Waypoint* wp = new Waypoint(id, x, y, z, yaw, autocontinue, current);
addWaypoint(wp);
}
}
......@@ -122,7 +133,9 @@ void WaypointList::setWaypoint(int uasId, int id, double x, double y, double z,
void WaypointList::waypointReached(UASInterface* uas, int waypointId)
{
Q_UNUSED(uas);
if (waypoints.size() > waypointId)
qDebug() << "Waypoint reached: " << waypointId;
/*if (waypoints.size() > waypointId)
{
if (waypoints[waypointId]->autocontinue == true)
{
......@@ -149,7 +162,7 @@ void WaypointList::waypointReached(UASInterface* uas, int waypointId)
qDebug() << "NEW WAYPOINT SET";
}
}
}*/
}
void WaypointList::transmit()
......@@ -160,12 +173,13 @@ void WaypointList::transmit()
waypointNames.clear();
for(int i = 0; i < waypoints.size(); i++)
{
Waypoint* wp = waypoints[i];
waypointNames.insert(wp->id, wp->name);
//Waypoint* wp = waypoints[i];
/*waypointNames.insert(wp->id, wp->name);
emit waypointChanged(wp);
if (wp->current)
emit currentWaypointChanged(wp->id);
emit currentWaypointChanged(wp->id);*/
}
while(waypoints.size()>0)
{
removeWaypoint(waypoints[0]);
......@@ -180,11 +194,11 @@ void WaypointList::add()
{
if (waypoints.size() > 0)
{
addWaypoint(new Waypoint("New waypoint", waypoints.size(), 0.0, 0.1, -0.5, 0.0, false, false));
addWaypoint(new Waypoint(waypoints.size(), 0.0, 0.1, -0.5, 0.0, false, false));
}
else
{
addWaypoint(new Waypoint("New waypoint", waypoints.size(), 0.0, 0.0, -0.5, 360.0, false, true));
addWaypoint(new Waypoint(waypoints.size(), 0.0, 0.0, -0.5, 360.0, false, true));
}
}
}
......@@ -196,7 +210,7 @@ void WaypointList::addWaypoint(Waypoint* wp)
removeWaypoint(wp);
}
waypoints.insert(wp->id, wp);
waypoints.insert(wp->getId(), wp);
if (!wpViews.contains(wp))
{
......@@ -231,17 +245,9 @@ void WaypointList::redrawList()
}
}
void WaypointList::debugOutputWaypoints()
{
for (int i = 0; i < waypoints.size(); i++)
{
qDebug() << i << " " << waypoints[i]->name;
}
}
void WaypointList::moveUp(Waypoint* wp)
{
int id = wp->id;
int id = wp->getId();
if (waypoints.size() > 1 && waypoints.size() > id)
{
Waypoint* temp = waypoints[id];
......@@ -249,15 +255,15 @@ void WaypointList::moveUp(Waypoint* wp)
{
waypoints[id] = waypoints[id-1];
waypoints[id-1] = temp;
waypoints[id-1]->id = id-1;
waypoints[id]->id = id;
waypoints[id-1]->setId(id-1);
waypoints[id]->setId(id);
}
else
{
waypoints[id] = waypoints[waypoints.size()-1];
waypoints[waypoints.size()-1] = temp;
waypoints[waypoints.size()-1]->id = waypoints.size()-1;
waypoints[id]->id = id;
waypoints[waypoints.size()-1]->setId(waypoints.size()-1);
waypoints[id]->setId(id);
}
redrawList();
}
......@@ -265,7 +271,7 @@ void WaypointList::moveUp(Waypoint* wp)
void WaypointList::moveDown(Waypoint* wp)
{
int id = wp->id;
int id = wp->getId();
if (waypoints.size() > 1 && waypoints.size() > id)
{
Waypoint* temp = waypoints[id];
......@@ -273,15 +279,15 @@ void WaypointList::moveDown(Waypoint* wp)
{
waypoints[id] = waypoints[id+1];
waypoints[id+1] = temp;
waypoints[id+1]->id = id+1;
waypoints[id]->id = id;
waypoints[id+1]->setId(id+1);
waypoints[id]->setId(id);
}
else
{
waypoints[id] = waypoints[0];
waypoints[0] = temp;
waypoints[0]->id = 0;
waypoints[id]->id = id;
waypoints[0]->setId(0);
waypoints[id]->setId(id);
}
redrawList();
}
......@@ -289,7 +295,7 @@ void WaypointList::moveDown(Waypoint* wp)
void WaypointList::removeWaypointAndName(Waypoint* wp)
{
waypointNames.remove(wp->id);
waypointNames.remove(wp->getId());
removeWaypoint(wp);
}
......@@ -297,10 +303,10 @@ void WaypointList::removeWaypoint(Waypoint* wp)
{
// Delete from list
if (wp != NULL){
waypoints.remove(wp->id);
for(int i = wp->id; i < waypoints.size(); i++)
waypoints.remove(wp->getId());
for(int i = wp->getId(); i < waypoints.size(); i++)
{
waypoints[i]->id = i;
waypoints[i]->setId(i);
}
// Remove from view
......@@ -318,15 +324,15 @@ void WaypointList::setCurrentWaypoint(Waypoint* wp)
{
if (waypoints[i] == wp)
{
waypoints[i]->current = true;
waypoints[i]->setCurrent(true);
// Retransmit waypoint
//uas->getWaypointManager().setWaypointActive(i);
}
else
{
if (waypoints[i]->current)
if (waypoints[i]->getCurrent())
{
waypoints[i]->current = false;
waypoints[i]->setCurrent(false);
WaypointView* widget = wpViews.find(waypoints[i]).value();
widget->removeCurrentCheck();
}
......@@ -361,7 +367,7 @@ void WaypointList::saveWaypoints()
for (int i = 0; i < waypoints.size(); i++)
{
Waypoint* wp = waypoints[i];
in << wp->name << "~" << wp->id << "~" << wp->x << "~" << wp->y << "~" << wp->z << "~" << wp->yaw << "~" << wp->autocontinue << "~" << wp->current << "\n";
in << "~" << wp->getId() << "~" << wp->getX() << "~" << wp->getY() << "~" << wp->getZ() << "~" << wp->getYaw() << "~" << wp->getAutoContinue() << "~" << wp->getCurrent() << "\n";
in.flush();
}
file.close();
......@@ -384,7 +390,7 @@ void WaypointList::loadWaypoints()
{
QStringList wpParams = in.readLine().split("~");
if (wpParams.size() == 8)
addWaypoint(new Waypoint(wpParams[0], 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)));
}
file.close();
}
......
......@@ -27,6 +27,7 @@ This file is part of the PIXHAWK project
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
......@@ -66,6 +67,9 @@ public slots:
void moveDown(Waypoint* wp);
void setCurrentWaypoint(Waypoint* wp);
/** @brief sets statusLabel string */
void updateStatusLabel(const QString &string);
//To be moved to UASWaypointManager (?)
void setWaypoint(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool current);
void addWaypoint(Waypoint* wp);
......
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>419</width>
<height>206</height>
<width>476</width>
<height>218</height>
</rect>
</property>
<property name="minimumSize">
......@@ -19,14 +19,14 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="100,0">
<layout class="QGridLayout" name="gridLayout" rowstretch="100,0,0,0">
<property name="margin">
<number>4</number>
</property>
<property name="spacing">
<number>4</number>
</property>
<item row="0" column="0" colspan="7">
<item row="0" column="0" colspan="8">
<widget class="QScrollArea" name="scrollArea">
<property name="widgetResizable">
<bool>true</bool>
......@@ -36,8 +36,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>409</width>
<height>158</height>
<width>466</width>
<height>148</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
......@@ -54,66 +54,73 @@
</widget>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>127</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="3">
<widget class="QToolButton" name="addButton">
<item row="2" column="6">
<widget class="QPushButton" name="readButton">
<property name="text">
<string>...</string>
<string>Read</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/list-add.svg</normaloff>:/images/actions/list-add.svg</iconset>
<normaloff>:/images/status/software-update-available.svg</normaloff>:/images/status/software-update-available.svg</iconset>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="saveButton">
<item row="2" column="7">
<widget class="QPushButton" name="transmitButton">
<property name="text">
<string>Save WPs</string>
<string>Write</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QPushButton" name="loadButton">
<item row="3" column="0" colspan="8">
<widget class="QLabel" name="statusLabel">
<property name="text">
<string>Load WPs</string>
<string>TextLabel</string>
</property>
</widget>
</item>
<item row="1" column="5">
<widget class="QPushButton" name="readButton">
<item row="2" column="5">
<widget class="QToolButton" name="addButton">
<property name="text">
<string>Read</string>
<string>...</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/status/software-update-available.svg</normaloff>:/images/status/software-update-available.svg</iconset>
<normaloff>:/images/actions/list-add.svg</normaloff>:/images/actions/list-add.svg</iconset>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QPushButton" name="transmitButton">
<item row="2" column="3">
<widget class="QPushButton" name="loadButton">
<property name="text">
<string>Write</string>
<string>Load WPs</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
</widget>
</item>
<item row="2" column="2">
<widget class="QPushButton" name="saveButton">
<property name="text">
<string>Save WPs</string>
</property>
</widget>
</item>
<item row="2" column="4">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>127</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
<action name="actionAddWaypoint">
<property name="icon">
......
......@@ -27,6 +27,7 @@ This file is part of the PIXHAWK project
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
......@@ -45,13 +46,13 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
this->wp = wp;
// Read values and set user interface
m_ui->name->setText(wp->name);
m_ui->xSpinBox->setValue(wp->x);
m_ui->ySpinBox->setValue(wp->y);
m_ui->zSpinBox->setValue(wp->z);
m_ui->yawSpinBox->setValue(wp->yaw);
m_ui->selectedBox->setChecked(wp->current);
m_ui->autoContinue->setChecked(wp->autocontinue);
m_ui->xSpinBox->setValue(wp->getX());
m_ui->ySpinBox->setValue(wp->getY());
m_ui->zSpinBox->setValue(wp->getZ());
m_ui->yawSpinBox->setValue(wp->getYaw());
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue());
m_ui->idLabel->setText(QString("%1").arg(wp->getId()));
connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
......@@ -64,7 +65,6 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(setAutoContinue(int)));
connect(m_ui->selectedBox, SIGNAL(clicked()), this, SLOT(setCurrent()));
connect(m_ui->name, SIGNAL(editingFinished()), this, SLOT(setText()));
}
void WaypointView::moveUp()
......@@ -86,9 +86,9 @@ void WaypointView::remove()
void WaypointView::setAutoContinue(int state)
{
if (state == 0)
wp->autocontinue = false;
wp->setAutocontinue(false);
else
wp->autocontinue = true;
wp->setAutocontinue(true);
emit waypointUpdated(wp);
}
......@@ -105,11 +105,6 @@ void WaypointView::setCurrent()
m_ui->selectedBox->setCheckState(Qt::Checked);
}
void WaypointView::setText()
{
wp->name = m_ui->name->text();
}
WaypointView::~WaypointView()
{
delete m_ui;
......
......@@ -27,6 +27,7 @@ This file is part of the PIXHAWK project
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
......@@ -56,7 +57,7 @@ public slots:
void remove();
void setAutoContinue(int);
void setCurrent();
void setText();
//void setText();
protected:
virtual void changeEvent(QEvent *e);
......
......@@ -155,7 +155,7 @@ QProgressBar::chunk#thrustBar {
<property name="title">
<string/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="0,25,5,0,0,0,0,0,0,0,0">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="0,0,5,0,0,0,0,0,0,0,0">
<property name="spacing">
<number>2</number>
</property>
......@@ -179,9 +179,9 @@ QProgressBar::chunk#thrustBar {
</widget>
</item>
<item>
<widget class="QLineEdit" name="name">
<widget class="QLabel" name="idLabel">
<property name="text">
<string>Name</string>
<string>TextLabel</string>
</property>
</widget>
</item>
......
......@@ -58,7 +58,7 @@ void WatchdogControl::updateWatchdog(int systemId, int watchdogId, unsigned int
// start the timeout timer
//watchdog.timeoutTimer_.reset();
qDebug() << "WATCHDOG RECEIVED";
//qDebug() << "WATCHDOG RECEIVED";
//qDebug() << "<-- received mavlink_watchdog_heartbeat_t " << msg->sysid << " / " << payload.watchdog_id << " / " << payload.process_count << std::endl;
}
......
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