Browse Source

Added support for custom waypoint and MAV icons, please extend and adapt to your own use

QGC4.4
lm 15 years ago
parent
commit
33f4226a6b
  1. 2
      qgroundcontrol.pro
  2. 4
      src/comm/MAVLinkSimulationLink.cc
  3. 39
      src/ui/MainWindow.cc
  4. 78
      src/ui/MapWidget.cc
  5. 23
      src/ui/MapWidget.h
  6. 84
      src/ui/map/MAV2DIcon.cc
  7. 44
      src/ui/map/MAV2DIcon.h
  8. 91
      src/ui/map/Waypoint2DIcon.cc
  9. 43
      src/ui/map/Waypoint2DIcon.h
  10. 6
      src/ui/map3D/Q3DWidget.cc
  11. 16
      src/ui/map3D/QMap3DWidget.cc

2
qgroundcontrol.pro

@ -158,7 +158,6 @@ HEADERS += src/MG.h \ @@ -158,7 +158,6 @@ HEADERS += src/MG.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/map/QGC2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \
@ -228,7 +227,6 @@ SOURCES += src/main.cc \ @@ -228,7 +227,6 @@ SOURCES += src/main.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/map/QGC2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/WaypointGlobal.cpp \
src/ui/WaypointGlobalView.cpp \

4
src/comm/MAVLinkSimulationLink.cc

@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop() @@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// GPS RAW
mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0, 2.5f, 0.1f);
mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0, 2.5f, 0.1f);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0);
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);

39
src/ui/MainWindow.cc

@ -657,14 +657,14 @@ void MainWindow::loadPixhawkView() @@ -657,14 +657,14 @@ void MainWindow::loadPixhawkView()
clearView();
// Engineer view, used in EMAV2009
// LINE CHART
if (linechartWidget)
// 3D map
if (map3DWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(map3DWidget);
}
}
@ -675,6 +675,18 @@ void MainWindow::loadPixhawkView() @@ -675,6 +675,18 @@ void MainWindow::loadPixhawkView()
controlDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// UAS LIST
if (listDockWidget)
{
@ -696,18 +708,6 @@ void MainWindow::loadPixhawkView() @@ -696,18 +708,6 @@ void MainWindow::loadPixhawkView()
waypointsDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
@ -715,13 +715,6 @@ void MainWindow::loadPixhawkView() @@ -715,13 +715,6 @@ void MainWindow::loadPixhawkView()
debugConsoleDockWidget->show();
}
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
// ONBOARD PARAMETERS
if (parametersDockWidget)
{

78
src/ui/MapWidget.cc

@ -37,6 +37,8 @@ This file is part of the QGROUNDCONTROL project @@ -37,6 +37,8 @@ This file is part of the QGROUNDCONTROL project
#include "ui_MapWidget.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "MAV2DIcon.h"
#include "Waypoint2DIcon.h"
#include "MG.h"
@ -53,7 +55,7 @@ MapWidget::MapWidget(QWidget *parent) : @@ -53,7 +55,7 @@ MapWidget::MapWidget(QWidget *parent) :
this->setFocusPolicy(Qt::StrongFocus);
// create MapControl
mc = new MapControl(QSize(320, 240));
mc = new qmapcontrol::MapControl(QSize(320, 240));
mc->showScale(true);
mc->showCoord(true);
mc->enablePersistentCache();
@ -62,21 +64,21 @@ MapWidget::MapWidget(QWidget *parent) : @@ -62,21 +64,21 @@ MapWidget::MapWidget(QWidget *parent) :
// create MapAdapter to get maps from
//TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17);
MapAdapter* mapadapter_overlay = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
// MAP BACKGROUND
mapadapter = new GoogleSatMapAdapter();
l = new MapLayer("Google Satellite", mapadapter);
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l = new qmapcontrol::MapLayer("Google Satellite", mapadapter);
mc->addLayer(l);
// STREET OVERLAY
overlay = new MapLayer("Overlay", mapadapter_overlay);
overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay);
overlay->setVisible(false);
mc->addLayer(overlay);
// WAYPOINT LAYER
// create a layer with the mapadapter and type GeometryLayer (for waypoints)
geomLayer = new GeometryLayer("Waypoints", mapadapter);
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
//
@ -188,6 +190,7 @@ MapWidget::MapWidget(QWidget *parent) : @@ -188,6 +190,7 @@ MapWidget::MapWidget(QWidget *parent) :
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
this, SLOT(addUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)),
this, SLOT(captureMapClick(const QMouseEvent*, const QPointF)));
@ -208,7 +211,7 @@ MapWidget::MapWidget(QWidget *parent) : @@ -208,7 +211,7 @@ MapWidget::MapWidget(QWidget *parent) :
pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3);
path = new LineString (wps, "UAV Path", pointPen);
path = new qmapcontrol::LineString (wps, "UAV Path", pointPen);
mc->layer("Waypoints")->addGeometry(path);
this->setVisible(false);
@ -224,7 +227,7 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -224,7 +227,7 @@ void MapWidget::mapproviderSelected(QAction* action)
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new OSMMapAdapter();
mapadapter = new qmapcontrol::OSMMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
@ -240,7 +243,7 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -240,7 +243,7 @@ void MapWidget::mapproviderSelected(QAction* action)
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new YahooMapAdapter();
mapadapter = new qmapcontrol::YahooMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
@ -256,7 +259,7 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -256,7 +259,7 @@ void MapWidget::mapproviderSelected(QAction* action)
QPointF a = mc->currentCoordinate();
mc->setZoom(0);
mapadapter = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
l->setMapAdapter(mapadapter);
mc->updateRequestNew();
@ -267,7 +270,7 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -267,7 +270,7 @@ void MapWidget::mapproviderSelected(QAction* action)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new GoogleMapAdapter();
mapadapter = new qmapcontrol::GoogleMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
@ -281,7 +284,7 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -281,7 +284,7 @@ void MapWidget::mapproviderSelected(QAction* action)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new GoogleSatMapAdapter();
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
@ -342,10 +345,19 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina @@ -342,10 +345,19 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
@ -360,7 +372,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina @@ -360,7 +372,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
}
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::captureGeometryClick(qmapcontrol::Geometry* geom, QPoint point){
Q_UNUSED(geom);
Q_UNUSED(point);
@ -369,21 +381,21 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ @@ -369,21 +381,21 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate){
Q_UNUSED(coordinate);
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
Point* point2Find;
qmapcontrol::Point* point2Find;
point2Find = wpIndex[geom->name()];
if (point2Find)
{
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <Point*> (geom);
point2Find = dynamic_cast <qmapcontrol::Point*> (geom);
if (point2Find)
{
point2Find->setCoordinate(coordinate);
@ -397,7 +409,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ @@ -397,7 +409,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
}
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
void MapWidget::captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate)
{
mc->setMouseMode(qmapcontrol::MapControl::Panning);
@ -417,10 +429,18 @@ MapWidget::~MapWidget() @@ -417,10 +429,18 @@ MapWidget::~MapWidget()
*/
void MapWidget::addUAS(UASInterface* uas)
{
mav = uas;
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
}
void MapWidget::activeUASSet(UASInterface* uas)
{
if (uas)
{
mav = uas;
path->setPen(new QPen(mav->getColor()));
}
}
/**
* Updates the global position of one MAV and append the last movement to the trail
*
@ -452,19 +472,19 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, @@ -452,19 +472,19 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Icon
QPen* pointpen = new QPen(uasColor);
CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen);
MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
geomLayer->addGeometry(p);
// Line
// A QPen also can use transparency
QList<Point*> points;
points.append(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// Add the Points and the QPen to a LineString
LineString* ls = new LineString(points, uas->getUASName(), linepen);
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
@ -472,10 +492,14 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, @@ -472,10 +492,14 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
}
else
{
CirclePoint* p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
MAV2DIcon* p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
if (p)
{
p->setCoordinate(QPointF(lat, lon));
p->setYaw(uas->getYaw());
}
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
}
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));

23
src/ui/MapWidget.h

@ -44,8 +44,6 @@ namespace Ui { @@ -44,8 +44,6 @@ namespace Ui {
class MapWidget;
}
using namespace qmapcontrol;
/**
* @brief 2D Moving map
*
@ -60,6 +58,7 @@ public: @@ -60,6 +58,7 @@ public:
public slots:
void addUAS(UASInterface* uas);
void activeUASSet(UASInterface* uas);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
@ -86,8 +85,8 @@ protected: @@ -86,8 +85,8 @@ protected:
QMenu* mapMenu;
QPushButton* mapButton;
MapControl* mc; ///< QMapControl widget
MapAdapter* mapadapter; ///< Adapter to load the map data
qmapcontrol::MapControl* mc; ///< QMapControl widget
qmapcontrol::MapAdapter* mapadapter; ///< Adapter to load the map data
qmapcontrol::Layer* l; ///< Current map layer (background)
qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
@ -98,18 +97,18 @@ protected: @@ -98,18 +97,18 @@ protected:
//Layer* gSatLayer;
QMap<int, CirclePoint*> uasIcons;
QMap<int, LineString*> uasTrails;
QMap<int, qmapcontrol::Point*> uasIcons;
QMap<int, qmapcontrol::LineString*> uasTrails;
UASInterface* mav;
quint64 lastUpdate;
protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
void createPathButtonClicked(bool checked);
void captureGeometryClick(Geometry*, QPoint);
void captureGeometryClick(qmapcontrol::Geometry*, QPoint);
void mapproviderSelected(QAction* action);
void captureGeometryDrag(Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(Geometry* geom, QPointF coordinate);
void captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate);
@ -122,9 +121,9 @@ protected: @@ -122,9 +121,9 @@ protected:
private:
Ui::MapWidget *m_ui;
QList<Point*> wps;
QHash <QString, Point*> wpIndex;
LineString* path;
QList<qmapcontrol::Point*> wps;
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
};

84
src/ui/map/MAV2DIcon.cc

@ -1,27 +1,83 @@ @@ -1,27 +1,83 @@
#include "MAV2DIcon.h"
#include <QPainter>
MAV2DIcon::MAV2DIcon(QGraphicsItem* parent) :
QGC2DIcon(parent)
MAV2DIcon::MAV2DIcon(qreal x, qreal y, int radius, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment),
yaw(0.0f)
{
size = QSize(radius, radius);
drawIcon(pen);
}
/**
* @return the bounding rectangle of the icon
*/
QRectF MAV2DIcon::boundingRect() const
MAV2DIcon::MAV2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment)
{
int radius = 10;
size = QSize(radius, radius);
drawIcon(pen);
}
MAV2DIcon::~MAV2DIcon()
{
delete mypixmap;
}
void MAV2DIcon::setPen(QPen* pen)
{
qreal penWidth = 1;
return QRectF(-10 - penWidth / 2, -10 - penWidth / 2,
20 + penWidth, 20 + penWidth);
mypen = pen;
drawIcon(pen);
}
/**
* @param painter QPainter to draw with
* @param option Visual style
* @param widget Parent widget
* @param yaw in radians, 0 = north, positive = clockwise
*/
void MAV2DIcon::paint(QPainter* painter, const QStyleOptionGraphicsItem* option, QWidget* widget)
void MAV2DIcon::setYaw(float yaw)
{
painter->drawRoundedRect(-10, -10, 20, 20, 5, 5);
this->yaw = yaw;
}
void MAV2DIcon::drawIcon(QPen* pen)
{
mypixmap = new QPixmap(radius+1, radius+1);
mypixmap->fill(Qt::transparent);
QPainter painter(mypixmap);
// DRAW MICRO AIR VEHICLE
QPointF p(radius/2, radius/2);
float waypointSize = radius;
QPolygonF poly(3);
// Top point
poly.replace(0, QPointF(p.x(), p.y()+waypointSize/2.0f));
// Right point
poly.replace(1, QPointF(p.x()-waypointSize/2.0f, p.y()-waypointSize/2.0f));
// Left point
poly.replace(2, QPointF(p.x()+waypointSize/2.0f, p.y() + waypointSize/2.0f));
// // Select color based on if this is the current waypoint
// if (list.at(i)->getCurrent())
// {
// color = QGC::colorCyan;//uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.8f));
// }
// else
// {
// color = uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.4f));
// }
//pen.setColor(color);
if (pen)
{
pen->setWidthF(2);
painter.setPen(*pen);
}
else
{
QPen pen2(Qt::yellow);
pen2.setWidth(2);
painter.setPen(pen2);
}
painter.setBrush(Qt::NoBrush);
painter.drawPolygon(poly);
}

44
src/ui/map/MAV2DIcon.h

@ -1,15 +1,49 @@ @@ -1,15 +1,49 @@
#ifndef MAV2DICON_H
#define MAV2DICON_H
#include "QGC2DIcon.h"
#include "qmapcontrol.h"
class MAV2DIcon : public QGC2DIcon
class MAV2DIcon : public qmapcontrol::Point
{
public:
explicit MAV2DIcon(QGraphicsItem* parent = 0);
/*!
*
* @param x longitude
* @param y latitude
* @param name name of the circle point
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
MAV2DIcon(qreal x, qreal y, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
//!
/*!
*
* @param x longitude
* @param y latitude
* @param radius the radius of the circle
* @param name name of the circle point
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
MAV2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
virtual ~MAV2DIcon();
//! sets the QPen which is used for drawing the circle
/*!
* A QPen can be used to modify the look of the drawn circle
* @param pen the QPen which should be used for drawing
* @see http://doc.trolltech.com/4.3/qpen.html
*/
virtual void setPen(QPen* pen);
void setYaw(float yaw);
void drawIcon(QPen* pen);
protected:
float yaw; ///< Yaw angle of the MAV
int radius; ///< Maximum dimension of the MAV icon
QRectF boundingRect() const;
void paint(QPainter*, const QStyleOptionGraphicsItem*, QWidget*);
};

91
src/ui/map/Waypoint2DIcon.cc

@ -1,31 +1,88 @@ @@ -1,31 +1,88 @@
#include "Waypoint2DIcon.h"
#include <QPainter>
#include <QDebug>
Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, int radius, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment),
yaw(0.0f),
radius(radius)
{
size = QSize(radius, radius);
drawIcon(pen);
}
Waypoint2DIcon::Waypoint2DIcon(QGraphicsItem* parent) :
QGC2DIcon(parent)
Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen)
: Point(x, y, name, alignment)
{
int radius = 10;
size = QSize(radius, radius);
drawIcon(pen);
}
/**
* @return the bounding rectangle of the icon
*/
QRectF Waypoint2DIcon::boundingRect() const
Waypoint2DIcon::~Waypoint2DIcon()
{
qreal penWidth = 1;
return QRectF(-10 - penWidth / 2, -10 - penWidth / 2,
20 + penWidth, 20 + penWidth);
delete mypixmap;
}
void Waypoint2DIcon::setPen(QPen* pen)
{
mypen = pen;
drawIcon(pen);
}
/**
* @param painter QPainter to draw with
* @param option Visual style
* @param widget Parent widget
* @param yaw in radians, 0 = north, positive = clockwise
*/
void Waypoint2DIcon::paint(QPainter* painter, const QStyleOptionGraphicsItem* option, QWidget* widget)
void Waypoint2DIcon::setYaw(float yaw)
{
qDebug() << __FILE__ << __LINE__ << "DRAWING";
painter->setPen(QPen(Qt::red));
painter->drawRoundedRect(-10, -10, 20, 20, 5, 5);
this->yaw = yaw;
}
void Waypoint2DIcon::drawIcon(QPen* pen)
{
mypixmap = new QPixmap(radius+1, radius+1);
mypixmap->fill(Qt::transparent);
QPainter painter(mypixmap);
// DRAW WAYPOINT
QPointF p(radius/2, radius/2);
float waypointSize = radius;
QPolygonF poly(4);
// Top point
poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f));
// Right point
poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y()));
// Bottom point
poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f));
poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));
// // Select color based on if this is the current waypoint
// if (list.at(i)->getCurrent())
// {
// color = QGC::colorCyan;//uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.8f));
// }
// else
// {
// color = uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.4f));
// }
//pen.setColor(color);
if (pen)
{
pen->setWidthF(2);
painter.setPen(*pen);
}
else
{
QPen pen2(Qt::red);
pen2.setWidth(2);
painter.setPen(pen2);
}
painter.setBrush(Qt::NoBrush);
float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
painter.drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * rad);
painter.drawPolygon(poly);
}

43
src/ui/map/Waypoint2DIcon.h

@ -2,16 +2,49 @@ @@ -2,16 +2,49 @@
#define WAYPOINT2DICON_H
#include <QGraphicsItem>
#include "QGC2DIcon.h"
#include "qmapcontrol.h"
class Waypoint2DIcon : public QGC2DIcon
class Waypoint2DIcon : public qmapcontrol::Point
{
public:
explicit Waypoint2DIcon(QGraphicsItem* parent = 0);
/*!
*
* @param x longitude
* @param y latitude
* @param name name of the circle point
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
Waypoint2DIcon(qreal x, qreal y, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
QRectF boundingRect() const;
void paint(QPainter*, const QStyleOptionGraphicsItem*, QWidget*);
//!
/*!
*
* @param x longitude
* @param y latitude
* @param radius the radius of the circle
* @param name name of the circle point
* @param alignment alignment (Middle or TopLeft)
* @param pen QPen for drawing
*/
Waypoint2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0);
virtual ~Waypoint2DIcon();
//! sets the QPen which is used for drawing the circle
/*!
* A QPen can be used to modify the look of the drawn circle
* @param pen the QPen which should be used for drawing
* @see http://doc.trolltech.com/4.3/qpen.html
*/
virtual void setPen(QPen* pen);
void setYaw(float yaw);
void drawIcon(QPen* pen);
protected:
float yaw; ///< Yaw angle of the MAV
int radius; ///<
};

6
src/ui/map3D/Q3DWidget.cc

@ -34,9 +34,9 @@ Q3DWidget::Q3DWidget(QWidget* parent) @@ -34,9 +34,9 @@ Q3DWidget::Q3DWidget(QWidget* parent)
, timerFuncData(NULL)
{
cameraPose.state = IDLE;
cameraPose.pan = 0.0f;
cameraPose.tilt = 180.0f;
cameraPose.distance = 10.0f;
cameraPose.pan = 50.0f;
cameraPose.tilt = 200.0f;
cameraPose.distance = 5.0f;
cameraPose.xOffset = 0.0f;
cameraPose.yOffset = 0.0f;
cameraPose.zOffset = 0.0f;

16
src/ui/map3D/QMap3DWidget.cc

@ -12,13 +12,13 @@ QMap3DWidget::QMap3DWidget(QWidget* parent) @@ -12,13 +12,13 @@ QMap3DWidget::QMap3DWidget(QWidget* parent)
: Q3DWidget(parent)
, uas(NULL)
, lastRedrawTime(0.0)
, displayGrid(false)
, displayGrid(true)
, displayTrail(false)
, lockCamera(false)
{
setFocusPolicy(Qt::StrongFocus);
initialize(10, 10, 1000, 900, 10.0f);
initialize(10, 10, 1000, 900, 15.0f);
setCameraParams(0.05f, 0.5f, 0.01f, 0.5f, 30.0f, 0.01f, 400.0f);
setDisplayFunc(display, this);
@ -61,16 +61,16 @@ QMap3DWidget::buildLayout(void) @@ -61,16 +61,16 @@ QMap3DWidget::buildLayout(void)
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
layout->setSpacing(2);
//layout->addWidget(mc, 0, 0, 1, 2);
layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 0, 0);
layout->addWidget(gridCheckBox, 1, 0);
layout->addWidget(trailCheckBox, 1, 1);
layout->addWidget(recenterButton, 1, 2);
layout->addWidget(lockCameraCheckBox, 1, 3);
// layout->addWidget(positionLabel, 1, 4);
layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 2);
layout->addWidget(recenterButton, 1, 3);
layout->addWidget(lockCameraCheckBox, 1, 4);
layout->setRowStretch(0, 100);
layout->setRowStretch(1, 1);
layout->setColumnStretch(0, 1);
layout->setColumnStretch(1, 50);
//layout->setColumnStretch(0, 1);
layout->setColumnStretch(2, 50);
setLayout(layout);
connect(gridCheckBox, SIGNAL(stateChanged(int)),

Loading…
Cancel
Save