Commit 9683bd14 authored by pixhawk's avatar pixhawk

Working WP manager -> map waypoint updates. List reordering does not work yet....

Working WP manager -> map waypoint updates. List reordering does not work yet. Next steps: List reordering, map -> WP manager updates, better waypoint graphs
parent 6a9f84b3
......@@ -188,7 +188,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \
src/ui/mission/QGCMissionDoWidget.ui \
src/ui/mission/QGCMissionConditionWidget.ui
src/ui/mission/QGCMissionConditionWidget.ui \
src/ui/map/QGCMapToolbar.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -301,7 +302,8 @@ HEADERS += src/MG.h \
src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \
src/ui/mavlink/QGCMAVLinkTextEdit.h
src/ui/mavlink/QGCMAVLinkTextEdit.h \
src/ui/map/QGCMapToolbar.h
# src/ui/map/Waypoint2DIcon.h \
......@@ -429,7 +431,8 @@ SOURCES += src/main.cc \
src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/mavlink/QGCMAVLinkTextEdit.cc
src/ui/mavlink/QGCMAVLinkTextEdit.cc \
src/ui/map/QGCMapToolbar.cc
# src/ui/map/Waypoint2DIcon.cc
macx|win32-msvc2008::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
contains(DEPENDENCIES_PRESENT, osg) {
......
......@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1, double _param2, double _param3, double _param4,
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action)
bool _autocontinue, bool _current, MAV_FRAME _frame, MAV_CMD _action, const QString& _description)
: id(_id),
x(_x),
y(_y),
......@@ -48,7 +48,8 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1,
orbit(_param3),
param1(_param1),
param2(_param2),
name(QString("WP%1").arg(id, 2, 10, QChar('0')))
name(QString("WP%1").arg(id, 2, 10, QChar('0'))),
description(_description)
{
}
......@@ -70,15 +71,15 @@ void Waypoint::save(QTextStream &saveStream)
position = position.arg(z, 0, 'g', 18);
QString parameters("%1\t%2\t%3\t%4");
parameters = parameters.arg(param1, 0, 'g', 18).arg(param2, 0, 'g', 18).arg(orbit, 0, 'g', 18).arg(yaw, 0, 'g', 18);
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE>
// FORMAT: <INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE> <DESCRIPTION>
// as documented here: http://qgroundcontrol.org/waypoint_protocol
saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n";
saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n";
}
bool Waypoint::load(QTextStream &loadStream)
{
const QStringList &wpParams = loadStream.readLine().split("\t");
if (wpParams.size() == 12) {
if (wpParams.size() == 13) {
this->id = wpParams[0].toInt();
this->current = (wpParams[1].toInt() == 1 ? true : false);
this->frame = (MAV_FRAME) wpParams[2].toInt();
......@@ -91,6 +92,7 @@ bool Waypoint::load(QTextStream &loadStream)
this->y = wpParams[9].toDouble();
this->z = wpParams[10].toDouble();
this->autocontinue = (wpParams[11].toInt() == 1 ? true : false);
//this->description = wpParams[12];
return true;
}
return false;
......
......@@ -44,7 +44,7 @@ class Waypoint : public QObject
public:
Waypoint(quint16 id = 0, double x = 0.0, double y = 0.0, double z = 0.0, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0,
bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT);
bool autocontinue = true, bool current = false, MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_CMD action=MAV_CMD_NAV_WAYPOINT, const QString& description=QString(""));
~Waypoint();
quint16 getId() const {
......@@ -119,6 +119,9 @@ public:
const QString& getName() const {
return name;
}
const QString& getDescription() const {
return description;
}
/** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType();
......@@ -141,6 +144,7 @@ protected:
double param2;
int turns;
QString name;
QString description;
public slots:
void setId(quint16 id);
......
......@@ -294,6 +294,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
Waypoint *t = waypoints[seq];
waypoints.remove(seq);
delete t;
t = NULL;
for(int i = seq; i < waypoints.size(); i++) {
waypoints[i]->setId(i);
......
#include "QGCMapToolbar.h"
#include "ui_QGCMapToolbar.h"
QGCMapToolbar::QGCMapToolbar(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMapToolbar)
{
ui->setupUi(this);
}
QGCMapToolbar::~QGCMapToolbar()
{
delete ui;
}
#ifndef QGCMAPTOOLBAR_H
#define QGCMAPTOOLBAR_H
#include <QWidget>
namespace Ui {
class QGCMapToolbar;
}
class QGCMapToolbar : public QWidget
{
Q_OBJECT
public:
explicit QGCMapToolbar(QWidget *parent = 0);
~QGCMapToolbar();
private:
Ui::QGCMapToolbar *ui;
};
#endif // QGCMAPTOOLBAR_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMapToolbar</class>
<widget class="QWidget" name="QGCMapToolbar">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>617</width>
<height>28</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>2</number>
</property>
<item>
<widget class="QPushButton" name="goToLatLonButton">
<property name="text">
<string>Lat/Lon</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="goToHomeButton">
<property name="text">
<string>Home</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="editButton">
<property name="text">
<string>Edit</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="setHomeButton">
<property name="text">
<string>Set Home</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="latLonLabel">
<property name="text">
<string>Mouse Coordinate</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
This diff is collapsed.
#ifndef QGCMAPWIDGET_H
#define QGCMAPWIDGET_H
#include <QMap>
#include "opmapcontrol.h"
class UASInterface;
class UASWaypointManager;
class Waypoint;
/**
* @brief Class representing a 2D map using aerial imagery
*/
class QGCMapWidget : public mapcontrol::OPMapWidget
{
Q_OBJECT
......@@ -13,18 +19,43 @@ public:
~QGCMapWidget();
signals:
void homePositionChanged(double latitude, double longitude, double altitude);
public slots:
/** @brief Add system to map view */
void addUAS(UASInterface* uas);
/** @brief Update the global position of a system */
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Update the type, size, etc. of this system */
void updateSystemSpecs(int uas);
/** @brief Update the whole system state */
void updateSelectedSystem(int uas);
/** @brief Change current system in focus / editing */
void activeUASSet(UASInterface* uas);
/** @brief Show a dialog to jump to given GPS coordinates */
void showGoToDialog();
/** @brief Update this waypoint for this UAS */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief Update the whole waypoint */
void updateWaypointList(int uas);
/** @brief Update the home position on the map */
void updateHomePosition(double latitude, double longitude, double altitude);
protected:
/** @brief Update the attitude of this system */
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec);
/** @brief Update the highlighting of the currently controlled system */
void updateSelectedSystem(int uas);
/** @brief Set the current mouse position on the map as new home position */
UASWaypointManager* currWPManager; ///< The current waypoint manager
QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons;
QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints;
// enum editMode {
// NONE,
// WAYPOINTS,
// SWEEP,
// UAVS,
// HOME,
// SAFE_AREA
// };
// enum editMode currEditMode; ///< The current edit mode on the map
};
......
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