From 92b9acd6e81109df40175d870315fee44457f98b Mon Sep 17 00:00:00 2001 From: jb Date: Fri, 27 Apr 2012 15:55:06 +0100 Subject: [PATCH 001/116] GCS - Added support for map ripping --- .../src/mapwidget/mapgraphicitem.cpp | 8 +-- .../opmapcontrol/src/mapwidget/mapripper.cpp | 63 ++++++++++++------- .../opmapcontrol/src/mapwidget/mapripper.h | 1 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 13 ++++ .../src/plugins/opmap/opmapgadgetwidget.h | 2 + 5 files changed, 60 insertions(+), 27 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 7c7984aa0..1df30d653 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -196,7 +196,7 @@ namespace mapcontrol } } - else if(isSelected && !selectionStart.IsEmpty() && (event->modifiers() == Qt::AltModifier || event->modifiers() == Qt::ShiftModifier)) + else if(isSelected && !selectionStart.IsEmpty() && (event->modifiers() == Qt::ControlModifier || event->modifiers() == Qt::ShiftModifier)) { selectionEnd = FromLocalToLatLng(event->pos().x(), event->pos().y()); { @@ -217,10 +217,10 @@ namespace mapcontrol { - + qDebug()<modifiers(); if(!IsMouseOverMarker()) { - if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::AltModifier)||(event->modifiers()==Qt::ShiftModifier))) + if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) { core->mouseDown.SetX(event->pos().x()); core->mouseDown.SetY(event->pos().y()); @@ -232,7 +232,7 @@ namespace mapcontrol this->update(); } - else if(!isSelected && ((event->modifiers()==Qt::AltModifier)||(event->modifiers()==Qt::ShiftModifier))) + else if(!isSelected && ((event->modifiers()==Qt::ControlModifier)||(event->modifiers()==Qt::ShiftModifier))) { isSelected = true; SetSelectedArea (internals::RectLatLng::Empty); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 00a2053cd..41518b81f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -28,7 +28,7 @@ namespace mapcontrol { - MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core) +MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core),yesToAll(false) { if(!rect.IsEmpty()) { @@ -46,32 +46,49 @@ namespace mapcontrol connect(this,SIGNAL(finished()),this,SLOT(finish())); emit numberOfTilesChanged(0,0); } + else + QMessageBox::information(new QWidget(),"No valid selection","Please select the area of the map to rip with Mouse+Control key"); } - void MapRipper::finish() +void MapRipper::finish() +{ + if(zoomProjection()->GetAreaTileList(area,zoom,0); - this->start(); - } - else - { - progressForm->close(); - delete progressForm; - this->deleteLater(); - } - } + QMessageBox msgBox; + msgBox.setText(QString("Continue Ripping at zoom level %1?").arg(zoom)); + // msgBox.setInformativeText("Do you want to save your changes?"); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No | QMessageBox::YesAll); + msgBox.setDefaultButton(QMessageBox::Yes); + ret = msgBox.exec(); + } + else + ret=QMessageBox::Yes; + if(ret==QMessageBox::Yes) + { + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else if(ret==QMessageBox::YesAll) + { + yesToAll=true; + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else + { + progressForm->close(); + delete progressForm; + this->deleteLater(); + } } + else + yesToAll=false; +} void MapRipper::run() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index 6b2087a12..313156863 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -50,6 +50,7 @@ namespace mapcontrol MapRipForm * progressForm; int maxzoom; internals::Core * core; + bool yesToAll; signals: void percentageChanged(int const& perc); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index abc51de20..2bae793a5 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -428,6 +428,10 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addAction(reloadAct); + menu.addSeparator(); + + menu.addAction(ripAct); + menu.addSeparator(); QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); @@ -1410,6 +1414,10 @@ void OPMapGadgetWidget::createActions() reloadAct->setStatusTip(tr("Reload the map tiles")); connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); + ripAct = new QAction(tr("&Rip map"), this); + ripAct->setStatusTip(tr("Rip the map tiles")); + connect(ripAct, SIGNAL(triggered()), this, SLOT(onRipAct_triggered())); + copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this); copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard")); connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered())); @@ -1682,6 +1690,11 @@ void OPMapGadgetWidget::onReloadAct_triggered() m_map->ReloadMap(); } +void OPMapGadgetWidget::onRipAct_triggered() +{ + m_map->RipMap(); +} + void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() { QClipboard *clipboard = QApplication::clipboard(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 24f638a80..8d374acdc 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -187,6 +187,7 @@ private slots: * @brief mouse right click context menu signals */ void onReloadAct_triggered(); + void onRipAct_triggered(); void onCopyMouseLatLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLonToClipAct_triggered(); @@ -282,6 +283,7 @@ private: QAction *closeAct1; QAction *closeAct2; QAction *reloadAct; + QAction *ripAct; QAction *copyMouseLatLonToClipAct; QAction *copyMouseLatToClipAct; QAction *copyMouseLonToClipAct; From 0bca2dbba6fd243b93a002b98a3c5a400a2df668 Mon Sep 17 00:00:00 2001 From: jb Date: Mon, 30 Apr 2012 14:57:06 +0100 Subject: [PATCH 002/116] GCS some improvements to the ripping function of the map library. --- .../opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 7 ------- .../opmapcontrol/src/mapwidget/mapripform.cpp | 1 + .../libs/opmapcontrol/src/mapwidget/mapripform.h | 2 ++ .../libs/opmapcontrol/src/mapwidget/mapripform.ui | 8 ++++---- .../libs/opmapcontrol/src/mapwidget/mapripper.cpp | 15 ++++++++++++++- .../libs/opmapcontrol/src/mapwidget/mapripper.h | 2 ++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 8 +++++--- 7 files changed, 28 insertions(+), 15 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 1df30d653..d4c548015 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -216,8 +216,6 @@ namespace mapcontrol void MapGraphicItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { - - qDebug()<modifiers(); if(!IsMouseOverMarker()) { if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) @@ -431,11 +429,6 @@ namespace mapcontrol } } } - // painter->drawRect(core->GetrenderOffset().X()-lastimagepoint.X()-3,core->GetrenderOffset().Y()-lastimagepoint.Y()-3,lastimage.width(),lastimage.height()); -// painter->setPen(Qt::red); -// painter->drawLine(-10,-10,10,10); -// painter->drawLine(10,10,-10,-10); -// painter->drawRect(boundingRect().adjusted(100,100,-100,-100)); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp index bbd1725a1..b2baf5b21 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp @@ -33,6 +33,7 @@ MapRipForm::MapRipForm(QWidget *parent) : ui(new Ui::MapRipForm) { ui->setupUi(this); + connect(ui->cancelButton,SIGNAL(clicked()),this,SIGNAL(cancelRequest())); } MapRipForm::~MapRipForm() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h index b1ff3637f..6f150fd4d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h @@ -44,6 +44,8 @@ public slots: void SetPercentage(int const& perc); void SetProvider(QString const& prov,int const& zoom); void SetNumberOfTiles(int const& total,int const& actual); +signals: + void cancelRequest(); private: Ui::MapRipForm *ui; }; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui index 8100f8651..1fa6a935d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui @@ -6,7 +6,7 @@ 0 0 - 392 + 521 133 @@ -18,7 +18,7 @@ 20 60 - 371 + 481 23 @@ -31,7 +31,7 @@ 30 10 - 321 + 481 16 @@ -55,7 +55,7 @@ - 280 + 220 100 75 23 diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 41518b81f..bbda543d6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -34,11 +34,13 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect) { type=core->GetMapType(); progressForm=new MapRipForm; + connect(progressForm,SIGNAL(cancelRequest()),this,SLOT(stopFetching())); area=rect; zoom=core->Zoom(); maxzoom=core->MaxZoom(); points=core->Projection()->GetAreaTileList(area,zoom,0); this->start(); + cancel=false; progressForm->show(); connect(this,SIGNAL(percentageChanged(int)),progressForm,SLOT(SetPercentage(int))); connect(this,SIGNAL(numberOfTilesChanged(int,int)),progressForm,SLOT(SetNumberOfTiles(int,int))); @@ -51,7 +53,7 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect) } void MapRipper::finish() { - if(zoomclose(); + delete progressForm; + this->deleteLater(); + } } @@ -136,4 +143,10 @@ void MapRipper::finish() QThread::msleep(sleep); } } + + void MapRipper::stopFetching() + { + QMutexLocker locker(&mutex); + cancel=true; + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index 313156863..2c426d3d1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -51,6 +51,7 @@ namespace mapcontrol int maxzoom; internals::Core * core; bool yesToAll; + QMutex mutex; signals: void percentageChanged(int const& perc); @@ -59,6 +60,7 @@ namespace mapcontrol public slots: + void stopFetching(); void finish(); }; } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 2bae793a5..4199daab7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -474,12 +474,14 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); */ - - menu.addAction(showSafeAreaAct); + QMenu safeArea("Safety Area definitions"); + // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); for (int i = 0; i < safeAreaAct.count(); i++) safeAreaSubMenu.addAction(safeAreaAct.at(i)); - menu.addMenu(&safeAreaSubMenu); + safeArea.addMenu(&safeAreaSubMenu); + safeArea.addAction(showSafeAreaAct); + menu.addMenu(&safeArea); menu.addSeparator(); From 9f1afacdafe55f82bdc88b5698a24baf8bc8a092 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 8 May 2012 16:22:06 +0100 Subject: [PATCH 003/116] Minor cleaning --- .../opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 12 +++++++++++- .../libs/opmapcontrol/src/mapwidget/mapgraphicitem.h | 2 ++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index d4c548015..91623b03f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -40,6 +40,7 @@ namespace mapcontrol core->SetCurrentRegion(internals::Rectangle(0, 0, maprect.width(), maprect.height())); core->SetMapType(MapType::GoogleHybrid); this->SetZoom(2); + this->setFlag(ItemIsFocusable); connect(core,SIGNAL(OnNeedInvalidation()),this,SLOT(Core_OnNeedInvalidation())); connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh())); connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); @@ -238,7 +239,6 @@ namespace mapcontrol selectionStart = FromLocalToLatLng(event->pos().x(), event->pos().y()); } } - } void MapGraphicItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { @@ -272,6 +272,16 @@ namespace mapcontrol } } + void MapGraphicItem::keyPressEvent(QKeyEvent *event) + { + if(event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier)) + this->setCursor(Qt::CrossCursor); + } + void MapGraphicItem::keyReleaseEvent(QKeyEvent *event) + { + if((event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier))==0) + this->setCursor(Qt::ArrowCursor); + } bool MapGraphicItem::SetZoomToFitRect(internals::RectLatLng const& rect) { int maxZoom = core->GetMaxZoomToFitRect(rect); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index 034b1c8b8..c3c235617 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -107,6 +107,8 @@ namespace mapcontrol void wheelEvent ( QGraphicsSceneWheelEvent * event ); void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); bool IsMouseOverMarker()const{return isMouseOverMarker;} + void keyPressEvent ( QKeyEvent * event ); + void keyReleaseEvent ( QKeyEvent * event ); /** * @brief Returns current map zoom From bb7e85cf2c67c6d7a8175524872c1bb178a0cd71 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 17 May 2012 17:27:08 +0100 Subject: [PATCH 004/116] GCS - Changes to the map lib. Preparatory steps to allow WPs to be defined relative to home. GPS fed UAV map item is only visible when diagnostics are enabled. Should make users not be confused by 2 UAVs on screen. --- .../src/internals/pureprojection.cpp | 26 ++++ .../src/internals/pureprojection.h | 3 + .../opmapcontrol/src/mapwidget/homeitem.cpp | 38 +++++- .../opmapcontrol/src/mapwidget/homeitem.h | 8 +- .../src/mapwidget/opmapwidget.cpp | 45 +++---- .../opmapcontrol/src/mapwidget/uavitem.cpp | 6 +- .../src/mapwidget/waypointitem.cpp | 111 +++++++++++++++--- .../opmapcontrol/src/mapwidget/waypointitem.h | 17 ++- .../src/plugins/opmap/opmapgadgetwidget.cpp | 46 ++++---- 9 files changed, 222 insertions(+), 78 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 432defd06..f362321d1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -215,6 +215,13 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) Lat /= (PI / 180); Lng /= (PI / 180); } + double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) + { + return fmod(atan2(sin(p1.Lng()-p2.Lng())*cos(p2.Lat()), + cos(p1.Lat())*sin(p2.Lat())-sin(p1.Lat())*cos(p2.Lat())*cos(p1.Lng()-p2.Lng())), 2*PI); + + } + double PureProjection::DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) { double R = 6371; // km @@ -229,4 +236,23 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) double d = R * c; return d; } + + void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &dX,double &dY) + { + dX=DistanceBetweenLatLng(p1,p2)*sin(courseBetweenLatLng(p1,p2)); + dY=DistanceBetweenLatLng(p1,p2)*sin(courseBetweenLatLng(p1,p2)); + } + + PointLatLng PureProjection::translate(PointLatLng p1,double dX,double dY) + { + PointLatLng origin=p1; + PointLatLng ret; + double d=sqrt(pow(dX,2)+pow(dY,2)); + double tc=atan2(dY,dX); + ret.SetLat(asin(sin(origin.Lat())*cos(d)+cos(origin.Lat())*sin(d)*cos(tc))); + double dlon=atan2(sin(tc)*sin(d)*cos(origin.Lat()),cos(d)-sin(origin.Lat())*sin(p1.Lat())); + ret.SetLng(fmod(origin.Lng()-dlon +PI,2*PI )-PI); + return ret; + } + } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h index 4ab806a62..013bc906c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -81,6 +81,9 @@ public: void FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng); static double DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2); + PointLatLng translate(PointLatLng p1, double dX, double dY); + double courseBetweenLatLng(const PointLatLng &p1, const PointLatLng &p2); + void offSetFromLatLngs(PointLatLng p1, PointLatLng p2, double &dX, double &dY); protected: static const double PI; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 815aa86f3..315aa55de 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -27,15 +27,20 @@ #include "homeitem.h" namespace mapcontrol { - HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent),showsafearea(true),safearea(1000),altitude(0) + HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent),showsafearea(true),safearea(1000),altitude(0),isDragging(false) { pic.load(QString::fromUtf8(":/markers/images/home2.svg")); pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); coord=internals::PointLatLng(50,50); + setToolTip("AAAA"); + qDebug()<<"HomeItem created type:"<localsafearea*2) return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); else return QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2); @@ -76,5 +81,34 @@ namespace mapcontrol localsafearea=safearea/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); } + void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + isDragging=true; + } + QGraphicsItem::mousePressEvent(event); + } + void HomeItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + isDragging=false; + emit homePositionChanged(coord); + } + QGraphicsItem::mouseReleaseEvent(event); + } + void HomeItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) + { + + if(isDragging) + { + coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + emit homePositionChanged(coord); + } + QGraphicsItem::mouseMoveEvent(event); + } } + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index 3c03396ee..eb16b6017 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -67,11 +67,15 @@ namespace mapcontrol int safearea; int localsafearea; int altitude; - + bool isDragging; + protected: + void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); + void mousePressEvent ( QGraphicsSceneMouseEvent * event ); + void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); public slots: signals: - + void homePositionChanged(internals::PointLatLng coord); }; } #endif // HOMEITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index c506532d4..2dff7074e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -40,6 +40,9 @@ namespace mapcontrol map=new MapGraphicItem(core,config); mscene.addItem(map); this->setScene(&mscene); + Home=new HomeItem(map,this); + Home->setParentItem(map); + setStyleSheet("QToolTip {font-size:8pt; color:yellow;background-color : transparent; padding:2px; border-width:2px; border-style:solid; border-radius:4px }"); this->adjustSize(); connect(map,SIGNAL(zoomChanged(double,double,double)),this,SIGNAL(zoomChanged(double,double,double))); connect(map->core,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)),this,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng))); @@ -70,12 +73,23 @@ namespace mapcontrol delete diagTimer; diagTimer=0; } + + if(GPS!=0) + { + delete GPS; + GPS=0; + } } else { diagTimer=new QTimer(); connect(diagTimer,SIGNAL(timeout()),this,SLOT(diagRefresh())); diagTimer->start(500); + if(GPS==0) + { + GPS=new GPSItem(map,this); + GPS->setParentItem(map); + } } } @@ -106,37 +120,10 @@ namespace mapcontrol } } - if(value && GPS==0) - { - GPS=new GPSItem(map,this); - GPS->setParentItem(map); - } - else if(!value) - { - if(GPS!=0) - { - delete GPS; - GPS=0; - } - - } } void OPMapWidget::SetShowHome(const bool &value) { - if(value && Home==0) - { - Home=new HomeItem(map,this); - Home->setParentItem(map); - } - else if(!value) - { - if(Home!=0) - { - delete Home; - Home=0; - } - - } + Home->setVisible(value); } void OPMapWidget::resizeEvent(QResizeEvent *event) @@ -329,12 +316,12 @@ namespace mapcontrol compass->setScale(0.1+0.05*(qreal)(this->size().width())/1000*(qreal)(this->size().height())/600); // compass->setTransformOriginPoint(compass->boundingRect().width(),compass->boundingRect().height()); compass->setFlag(QGraphicsItem::ItemIsMovable,true); + compass->setFlag(QGraphicsItem::ItemIsSelectable,true); mscene.addItem(compass); compass->setTransformOriginPoint(compass->boundingRect().width()/2,compass->boundingRect().height()/2); compass->setPos(55-compass->boundingRect().width()/2,55-compass->boundingRect().height()/2); compass->setZValue(3); compass->setOpacity(0.7); - } if(!value && compass) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index b28230da5..37dd4e345 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -36,6 +36,8 @@ namespace mapcontrol pic.load(uavPic); // Don't scale but trust the image we are given // pic=pic.scaled(50,33,Qt::IgnoreAspectRatio); + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); @@ -57,14 +59,14 @@ namespace mapcontrol { Q_UNUSED(option); Q_UNUSED(widget); - // painter->rotate(-90); painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); - // painter->drawRect(QRectF(-pic.width()/2,-pic.height()/2,pic.width()-1,pic.height()-1)); } + QRectF UAVItem::boundingRect()const { return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); } + void UAVItem::SetUAVPos(const internals::PointLatLng &position, const int &altitude) { if(coord.IsEmpty()) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 89c180f2d..da64afb90 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -25,9 +25,11 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "waypointitem.h" +#include "homeitem.h" + namespace mapcontrol { - WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, MapGraphicItem *map):coord(coord),reached(false),description(""),shownumber(true),isDragging(false),altitude(altitude),map(map) +WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(""),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { text=0; numberI=0; @@ -37,13 +39,31 @@ namespace mapcontrol this->setFlag(QGraphicsItem::ItemIsMovable,true); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); this->setFlag(QGraphicsItem::ItemIsSelectable,true); - // transf.translate(picture.width()/2,picture.height()); - // this->setTransform(transf); SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); + if(relativeCoord.isNull()) + { + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; + } + + double X; + double Y; + map->Projection()->offSetFromLatLngs(home->Coord(),coord,X,Y); + relativeCoord.setX(X); + relativeCoord.setY(Y); + + } + HomeItem * home=this->parent()->findChild(); + connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } - WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map) + WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { text=0; numberI=0; @@ -53,8 +73,58 @@ namespace mapcontrol this->setFlag(QGraphicsItem::ItemIsMovable,true); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); this->setFlag(QGraphicsItem::ItemIsSelectable,true); - //transf.translate(picture.width()/2,picture.height()); - // this->setTransform(transf); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + if(relativeCoord.isNull()) + { + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; + } + double X; + double Y; + map->Projection()->offSetFromLatLngs(home->Coord(),coord,X,Y); + relativeCoord.setX(X); + relativeCoord.setY(Y); + + } + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; + } + connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + } + + WayPointItem::WayPointItem(const QPoint &relativeCoord, const int &altitude, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map) + { + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; + } + connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + coord=map->Projection()->translate(home->Coord(),relativeCoord.x(),relativeCoord.y()); + myType=relative; + text=0; + numberI=0; + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + number=WayPointItem::snumber; + ++WayPointItem::snumber; + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); @@ -76,21 +146,18 @@ namespace mapcontrol { if(event->button()==Qt::LeftButton) { - text=new QGraphicsSimpleTextItem(this); + text=new QGraphicsSimpleTextItem(this); textBG=new QGraphicsRectItem(this); -// textBG->setBrush(Qt::white); -// textBG->setOpacity(0.5); + textBG->setBrush(Qt::yellow); - textBG->setBrush(QColor(255, 255, 255, 128)); - - text->setPen(QPen(Qt::red)); - text->setPos(10,-picture.height()); - textBG->setPos(10,-picture.height()); - text->setZValue(3); - RefreshToolTip(); - isDragging=true; - } + text->setPen(QPen(Qt::red)); + text->setPos(10,-picture.height()); + textBG->setPos(10,-picture.height()); + text->setZValue(3); + RefreshToolTip(); + isDragging=true; + } QGraphicsItem::mousePressEvent(event); } void WayPointItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) @@ -205,6 +272,14 @@ namespace mapcontrol this->update(); } } + + void WayPointItem::onHomePositionChanged(internals::PointLatLng homepos) + { + if(myType==relative) + { + coord=map->Projection()->translate(homepos,relativeCoord.x(),relativeCoord.y()); + } + } void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) { if (waypoint!=this) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index b9bee5ce5..ba9560015 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -33,6 +33,8 @@ #include "../internals/pointlatlng.h" #include "mapgraphicitem.h" #include +#include + namespace mapcontrol { /** @@ -46,15 +48,16 @@ class WayPointItem:public QObject,public QGraphicsItem Q_INTERFACES(QGraphicsItem) public: enum { Type = UserType + 1 }; + enum wptype {absolute,relative}; /** * @brief Constructer * * @param coord coordinates in LatLng of the Waypoint * @param altitude altitude of the WayPoint * @param map pointer to map to use - * @return + * @return */ - WayPointItem(internals::PointLatLng const& coord,int const& altitude,MapGraphicItem* map); + WayPointItem(internals::PointLatLng const& coord,int const& altitude,MapGraphicItem* map,wptype type=absolute); /** * @brief Constructer * @@ -64,7 +67,9 @@ public: * @param map pointer to map to use * @return */ - WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map); + WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map,wptype type=absolute); + WayPointItem(QPoint const& relativeCoord,int const& altitude,QString const& description,MapGraphicItem* map); + /** * @brief Returns the WayPoint description * @@ -149,9 +154,9 @@ protected: void mousePressEvent ( QGraphicsSceneMouseEvent * event ); void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); - private: internals::PointLatLng coord;//coordinates of this WayPoint + QPoint relativeCoord; bool reached; QString description; bool shownumber; @@ -167,6 +172,8 @@ private: QGraphicsRectItem* numberIBG; QTransform transf; + wptype myType; + public slots: /** * @brief Called when a WayPoint is deleted @@ -189,6 +196,8 @@ public slots: * @param waypoint a pointer to the WayPoint inserted */ void WPInserted(int const& number,WayPointItem* waypoint); + + void onHomePositionChanged(internals::PointLatLng); signals: /** * @brief fires when this WayPoint number changes (not fired if due to a auto-renumbering) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 4199daab7..5dc22bd59 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -178,13 +178,13 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed); // m_map->UAV->SetTrailType(UAVTrailType::ByDistance); + if(m_map->GPS) + { + m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds + m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters - m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds - m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters - - m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->GPS->SetTrailType(UAVTrailType::ByDistance); - + m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed); + } // ************** setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); @@ -269,8 +269,9 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - + if(m_map->GPS) + m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + m_map->WPCreate(); // ************** // create various context menu (mouse right click menu) actions @@ -390,22 +391,22 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) QString s; - if (!m_widget || !m_map) - return; + if (!m_widget || !m_map) + return; if (event->reason() != QContextMenuEvent::Mouse) return; // not a mouse click event // current mouse position QPoint p = m_map->mapFromGlobal(event->globalPos()); - m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); + m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); // m_context_menu_lat_lon = m_map->currentMousePosition(); if (!m_map->contentsRect().contains(p)) return; // the mouse click was not on the map // show the mouse position - s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7); + s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7); m_widget->labelMousePos->setText(s); // find out if we have a waypoint under the mouse cursor @@ -434,12 +435,12 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); - QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); - for (int i = 0; i < maxUpdateRateAct.count(); i++) - maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); - menu.addMenu(&maxUpdateRateSubMenu); + QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); + for (int i = 0; i < maxUpdateRateAct.count(); i++) + maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); + menu.addMenu(&maxUpdateRateSubMenu); - menu.addSeparator(); + menu.addSeparator(); switch (m_map_mode) { @@ -700,9 +701,11 @@ void OPMapGadgetWidget::updatePosition() // ************* // set the GPS icon position on the map - - m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position - m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading + if(m_map->GPS) + { + m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position + m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading + } // ************* } @@ -1886,7 +1889,8 @@ void OPMapGadgetWidget::onClearUAVtrailAct_triggered() return; m_map->UAV->DeleteTrail(); - m_map->GPS->DeleteTrail(); + if(m_map->GPS) + m_map->GPS->DeleteTrail(); } void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) From 8fbef19f5b5d8c5884ac50655d3d21c1d830841e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 26 May 2012 17:18:55 +0100 Subject: [PATCH 005/116] GCS - Map cleaning --- .../src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 91623b03f..540044476 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -216,9 +216,10 @@ namespace mapcontrol } void MapGraphicItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { - + qDebug()<<"mouse press"; if(!IsMouseOverMarker()) { + qDebug()<<"not over marker"; if(event->button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) { core->mouseDown.SetX(event->pos().x()); From 7a1501eea3a0d373e3a8dc37267867eeff321dbf Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 26 May 2012 21:23:53 +0100 Subject: [PATCH 006/116] GCS - Relative WPs are now working --- .../src/internals/pureprojection.cpp | 22 ++++++++++++++----- .../src/internals/pureprojection.h | 5 +++-- .../src/mapwidget/opmapwidget.cpp | 7 ++++++ .../opmapcontrol/src/mapwidget/opmapwidget.h | 9 ++++++++ .../src/mapwidget/waypointitem.cpp | 4 ++++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- 6 files changed, 41 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index f362321d1..2e90c903b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -243,15 +243,27 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) dY=DistanceBetweenLatLng(p1,p2)*sin(courseBetweenLatLng(p1,p2)); } + double PureProjection::myfmod(double x,double y) + { + return x - y*floor(x/y); + } + PointLatLng PureProjection::translate(PointLatLng p1,double dX,double dY) { - PointLatLng origin=p1; PointLatLng ret; double d=sqrt(pow(dX,2)+pow(dY,2)); - double tc=atan2(dY,dX); - ret.SetLat(asin(sin(origin.Lat())*cos(d)+cos(origin.Lat())*sin(d)*cos(tc))); - double dlon=atan2(sin(tc)*sin(d)*cos(origin.Lat()),cos(d)-sin(origin.Lat())*sin(p1.Lat())); - ret.SetLng(fmod(origin.Lng()-dlon +PI,2*PI )-PI); + double tc=(atan2(dY,dX)); + double lat1=p1.Lat()*M_PI/180; + double lon1=p1.Lng()*M_PI/180; + double R=6378137; + double lat2 = asin(sin(lat1)*cos(d/R) + cos(lat1)*sin(d/R)*cos(tc) ); + qDebug()< using namespace core; namespace internals @@ -106,7 +106,8 @@ protected: static double e3fn(const double &x); static double mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi); static qlonglong GetUTMzone(const double &lon); - +private: + double myfmod(double x, double y); }; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 2dff7074e..804e775af 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -211,6 +211,13 @@ namespace mapcontrol item->setParentItem(map); return item; } + WayPointItem* OPMapWidget::WPCreate(const QPoint &relativeCoord, const int &altitude, const QString &description) + { + WayPointItem* item=new WayPointItem(relativeCoord,altitude,description,map); + ConnectWP(item); + item->setParentItem(map); + return item; + } WayPointItem* OPMapWidget::WPInsert(const int &position) { WayPointItem* item=new WayPointItem(this->CurrentPosition(),0,map); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 5fd906de1..dcfee6264 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -279,6 +279,15 @@ namespace mapcontrol */ WayPointItem* WPCreate(internals::PointLatLng const& coord,int const& altitude, QString const& description); /** + * @brief Creates a new WayPoint + * + * @param coord the offset in meters to the home position + * @param altitude the Altitude of the WayPoint + * @param description the description of the WayPoint + * @return WayPointItem a pointer to the WayPoint created + */ + WayPointItem *WPCreate(const QPoint &relativeCoord, const int &altitude, const QString &description); + /** * @brief Inserts a new WayPoint on the specified position * * @param position index of the WayPoint diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index da64afb90..5e90f1b49 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -278,6 +278,10 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(myType==relative) { coord=map->Projection()->translate(homepos,relativeCoord.x(),relativeCoord.y()); + emit WPValuesChanged(this); + RefreshPos(); + RefreshToolTip(); + this->update(); } } void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 5dc22bd59..5f96c325a 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -271,7 +271,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - m_map->WPCreate(); + m_map->WPCreate(QPoint(1000,1000),10,"aaa"); // ************** // create various context menu (mouse right click menu) actions From 28b754183fafee26c4b103e2e4ac54a73c14f2e5 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 27 May 2012 21:55:47 +0100 Subject: [PATCH 007/116] GCS - MapLib change relative waypoint to distance and bearing definition --- .../src/internals/pureprojection.cpp | 23 +++-- .../src/internals/pureprojection.h | 2 +- .../src/mapwidget/opmapwidget.cpp | 4 +- .../opmapcontrol/src/mapwidget/opmapwidget.h | 2 +- .../src/mapwidget/waypointitem.cpp | 85 ++++++++++--------- .../opmapcontrol/src/mapwidget/waypointitem.h | 11 ++- 6 files changed, 72 insertions(+), 55 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 2e90c903b..0151a3656 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -217,8 +217,13 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) } double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) { - return fmod(atan2(sin(p1.Lng()-p2.Lng())*cos(p2.Lat()), - cos(p1.Lat())*sin(p2.Lat())-sin(p1.Lat())*cos(p2.Lat())*cos(p1.Lng()-p2.Lng())), 2*PI); + double lon1=p1.Lng()* (PI / 180);; + double lat1=p1.Lat()* (PI / 180);; + double lon2=p2.Lng()* (PI / 180);; + double lat2=p2.Lat()* (PI / 180);; + + return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2), + cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*PI); } @@ -237,22 +242,22 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) return d; } - void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &dX,double &dY) + void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &distance,double &bearing) { - dX=DistanceBetweenLatLng(p1,p2)*sin(courseBetweenLatLng(p1,p2)); - dY=DistanceBetweenLatLng(p1,p2)*sin(courseBetweenLatLng(p1,p2)); - } + distance=DistanceBetweenLatLng(p1,p2)*1000; + bearing=courseBetweenLatLng(p1,p2); + } double PureProjection::myfmod(double x,double y) { return x - y*floor(x/y); } - PointLatLng PureProjection::translate(PointLatLng p1,double dX,double dY) + PointLatLng PureProjection::translate(PointLatLng p1,double distance,double bearing) { PointLatLng ret; - double d=sqrt(pow(dX,2)+pow(dY,2)); - double tc=(atan2(dY,dX)); + double d=distance; + double tc=bearing; double lat1=p1.Lat()*M_PI/180; double lon1=p1.Lng()*M_PI/180; double R=6378137; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h index c0965c3b2..5b2406225 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -81,7 +81,7 @@ public: void FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng); static double DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2); - PointLatLng translate(PointLatLng p1, double dX, double dY); + PointLatLng translate(PointLatLng p1, double distance, double bearing); double courseBetweenLatLng(const PointLatLng &p1, const PointLatLng &p2); void offSetFromLatLngs(PointLatLng p1, PointLatLng p2, double &dX, double &dY); protected: diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 804e775af..b5c50f853 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -42,7 +42,7 @@ namespace mapcontrol this->setScene(&mscene); Home=new HomeItem(map,this); Home->setParentItem(map); - setStyleSheet("QToolTip {font-size:8pt; color:yellow;background-color : transparent; padding:2px; border-width:2px; border-style:solid; border-radius:4px }"); + setStyleSheet("QToolTip {font-size:8pt; color:blue;opacity: 223; padding:2px; border-width:2px; border-style:solid; border-color: rgb(170, 170, 127);border-radius:4px }"); this->adjustSize(); connect(map,SIGNAL(zoomChanged(double,double,double)),this,SIGNAL(zoomChanged(double,double,double))); connect(map->core,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)),this,SIGNAL(OnCurrentPositionChanged(internals::PointLatLng))); @@ -211,7 +211,7 @@ namespace mapcontrol item->setParentItem(map); return item; } - WayPointItem* OPMapWidget::WPCreate(const QPoint &relativeCoord, const int &altitude, const QString &description) + WayPointItem* OPMapWidget::WPCreate(const distBearing &relativeCoord, const int &altitude, const QString &description) { WayPointItem* item=new WayPointItem(relativeCoord,altitude,description,map); ConnectWP(item); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index dcfee6264..4d3668e18 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -286,7 +286,7 @@ namespace mapcontrol * @param description the description of the WayPoint * @return WayPointItem a pointer to the WayPoint created */ - WayPointItem *WPCreate(const QPoint &relativeCoord, const int &altitude, const QString &description); + WayPointItem *WPCreate(const distBearing &relativeCoord, const int &altitude, const QString &description); /** * @brief Inserts a new WayPoint on the specified position * diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 5e90f1b49..7dd982759 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -42,25 +42,19 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); - if(relativeCoord.isNull()) + + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) { - HomeItem* home=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - home=h; - } - - double X; - double Y; - map->Projection()->offSetFromLatLngs(home->Coord(),coord,X,Y); - relativeCoord.setX(X); - relativeCoord.setY(Y); - + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; } - HomeItem * home=this->parent()->findChild(); + + if(home) + map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) @@ -76,35 +70,22 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); - if(relativeCoord.isNull()) - { - HomeItem* home=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - home=h; - } - double X; - double Y; - map->Projection()->offSetFromLatLngs(home->Coord(),coord,X,Y); - relativeCoord.setX(X); - relativeCoord.setY(Y); - - } HomeItem* home=NULL; QList list=map->childItems(); foreach(QGraphicsItem * obj,list) { HomeItem* h=qgraphicsitem_cast (obj); if(h) - home=h; + home=h; + } + if(home) + { + map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } - connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } - WayPointItem::WayPointItem(const QPoint &relativeCoord, const int &altitude, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map) + WayPointItem::WayPointItem(const distBearing &relativeCoord, const int &altitude, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map) { HomeItem* home=NULL; QList list=map->childItems(); @@ -115,7 +96,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu home=h; } connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); - coord=map->Projection()->translate(home->Coord(),relativeCoord.x(),relativeCoord.y()); + coord=map->Projection()->translate(home->Coord(),relativeCoord.distante,relativeCoord.bearing); myType=relative; text=0; numberI=0; @@ -130,6 +111,15 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu RefreshPos(); } + void WayPointItem::changeWPType(wptype type) + { + myType=type; + emit WPValuesChanged(this); + RefreshPos(); + RefreshToolTip(); + this->update(); + } + QRectF WayPointItem::boundingRect() const { return QRectF(-picture.width()/2,-picture.height(),picture.width(),picture.height()); @@ -164,9 +154,18 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(event->button()==Qt::LeftButton) { + HomeItem* home=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + home=h; + } delete text; delete textBG; coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); isDragging=false; RefreshToolTip(); @@ -277,7 +276,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(myType==relative) { - coord=map->Projection()->translate(homepos,relativeCoord.x(),relativeCoord.y()); + coord=map->Projection()->translate(homepos,relativeCoord.distante,relativeCoord.bearing); emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); @@ -328,8 +327,14 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu } void WayPointItem::RefreshToolTip() { + QString type_str; + if(myType==relative) + type_str="Relative"; + else + type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nAltitude:%5").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(QString::number(altitude))); + QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distante) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str)); } int WayPointItem::snumber=0; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index ba9560015..2e82deb96 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -37,6 +37,12 @@ namespace mapcontrol { +struct distBearing +{ + double distante; + double bearing; +}; + /** * @brief A QGraphicsItem representing a WayPoint * @@ -68,7 +74,7 @@ public: * @return */ WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map,wptype type=absolute); - WayPointItem(QPoint const& relativeCoord,int const& altitude,QString const& description,MapGraphicItem* map); + WayPointItem(distBearing const& relativeCoord,int const& altitude,QString const& description,MapGraphicItem* map); /** * @brief Returns the WayPoint description @@ -149,6 +155,7 @@ public: ~WayPointItem(); static int snumber; + void changeWPType(wptype type); protected: void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); void mousePressEvent ( QGraphicsSceneMouseEvent * event ); @@ -156,7 +163,7 @@ protected: private: internals::PointLatLng coord;//coordinates of this WayPoint - QPoint relativeCoord; + distBearing relativeCoord; bool reached; QString description; bool shownumber; From 9024a21af7d6d131ad4b1283c8975180c35f7348 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 28 May 2012 14:12:06 +0100 Subject: [PATCH 008/116] GCS-MapLib - Reenabled waypoint features on the plugin. Added go_to_place feature to the plugin. --- .../src/internals/pureprojection.cpp | 1 - .../opmapcontrol/src/mapwidget/homeitem.cpp | 2 - .../src/mapwidget/mapgraphicitem.cpp | 2 - .../src/mapwidget/waypointitem.cpp | 47 ++++++------ .../opmapcontrol/src/mapwidget/waypointitem.h | 4 +- .../openpilotgcs/src/plugins/opmap/opmap.pro | 12 +-- .../src/plugins/opmap/opmap_widget.ui | 38 ++++++++++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 75 ++++++++++++------- .../src/plugins/opmap/opmapgadgetwidget.h | 37 +++++---- 9 files changed, 136 insertions(+), 82 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 0151a3656..ea29e171a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -262,7 +262,6 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) double lon1=p1.Lng()*M_PI/180; double R=6378137; double lat2 = asin(sin(lat1)*cos(d/R) + cos(lat1)*sin(d/R)*cos(tc) ); - qDebug()<setZValue(4); coord=internals::PointLatLng(50,50); setToolTip("AAAA"); - qDebug()<<"HomeItem created type:"<button() == config->DragButton && CanDragMap()&& !((event->modifiers()==Qt::ShiftModifier)||(event->modifiers()==Qt::ControlModifier))) { core->mouseDown.SetX(event->pos().x()); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 7dd982759..69a2287bb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -43,19 +43,19 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu RefreshToolTip(); RefreshPos(); - HomeItem* home=NULL; + myHome=NULL; QList list=map->childItems(); foreach(QGraphicsItem * obj,list) { HomeItem* h=qgraphicsitem_cast (obj); if(h) - home=h; + myHome=h; } - if(home) - map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + if(myHome) + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); - connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { @@ -70,33 +70,36 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); - HomeItem* home=NULL; + myHome=NULL; QList list=map->childItems(); foreach(QGraphicsItem * obj,list) { HomeItem* h=qgraphicsitem_cast (obj); if(h) - home=h; + myHome=h; } - if(home) + if(myHome) { - map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); - connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } } WayPointItem::WayPointItem(const distBearing &relativeCoord, const int &altitude, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map) { - HomeItem* home=NULL; + myHome=NULL; QList list=map->childItems(); foreach(QGraphicsItem * obj,list) { HomeItem* h=qgraphicsitem_cast (obj); if(h) - home=h; + myHome=h; + } + if(myHome) + { + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distante,relativeCoord.bearing); } - connect(home,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); - coord=map->Projection()->translate(home->Coord(),relativeCoord.distante,relativeCoord.bearing); myType=relative; text=0; numberI=0; @@ -154,18 +157,11 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(event->button()==Qt::LeftButton) { - HomeItem* home=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - home=h; - } delete text; delete textBG; coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - map->Projection()->offSetFromLatLngs(home->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + if(myHome) + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); isDragging=false; RefreshToolTip(); @@ -180,7 +176,10 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - text->setText(coord_str); + if(myHome) + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + QString relativeCoord_str = QString::number(relativeCoord.distante) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; + text->setText(coord_str+"\n"+relativeCoord_str); textBG->setRect(text->boundingRect()); emit WPValuesChanged(this); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 2e82deb96..41db14f93 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -42,7 +42,7 @@ struct distBearing double distante; double bearing; }; - +class HomeItem; /** * @brief A QGraphicsItem representing a WayPoint * @@ -178,7 +178,7 @@ private: QGraphicsSimpleTextItem* numberI; QGraphicsRectItem* numberIBG; QTransform transf; - + HomeItem * myHome; wptype myType; public slots: diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index 5bb709d01..caab7a52f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -15,8 +15,8 @@ HEADERS += opmapplugin.h \ opmapgadgetconfiguration.h \ opmapgadget.h \ opmapgadgetwidget.h \ -# opmap_waypointeditor_dialog.h \ -# opmap_edit_waypoint_dialog.h \ + opmap_waypointeditor_dialog.h \ + opmap_edit_waypoint_dialog.h \ opmap_zoom_slider_widget.h \ opmap_statusbar_widget.h \ opmap_overlay_widget.h @@ -27,8 +27,8 @@ SOURCES += opmapplugin.cpp \ opmapgadgetfactory.cpp \ opmapgadgetconfiguration.cpp \ opmapgadget.cpp \ - # opmap_waypointeditor_dialog.cpp \ - # opmap_edit_waypoint_dialog.cpp \ + opmap_waypointeditor_dialog.cpp \ + opmap_edit_waypoint_dialog.cpp \ opmap_zoom_slider_widget.cpp \ opmap_statusbar_widget.cpp \ opmap_overlay_widget.cpp @@ -37,8 +37,8 @@ OTHER_FILES += OPMapGadget.pluginspec FORMS += opmapgadgetoptionspage.ui \ opmap_widget.ui \ - # opmap_waypointeditor_dialog.ui \ - # opmap_edit_waypoint_dialog.ui \ + opmap_waypointeditor_dialog.ui \ + opmap_edit_waypoint_dialog.ui \ opmap_zoom_slider_widget.ui \ opmap_statusbar_widget.ui \ opmap_overlay_widget.ui diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui index b42b7fe0a..5dc841482 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui @@ -357,6 +357,32 @@ border-radius: 2px; + + + + + 8 + + + + Go To Place: + + + + + + + + + + ... + + + + :/opmap/images/waypoint.png:/opmap/images/waypoint.png + + + @@ -370,6 +396,18 @@ border-radius: 2px; + + + + + 8 + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 5f96c325a..be8d68fae 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -177,7 +177,6 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->UAV->SetTrailType(UAVTrailType::ByDistance); if(m_map->GPS) { m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds @@ -238,7 +237,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->progressBarMap->setMaximum(1); -/* + #if defined(Q_OS_MAC) #elif defined(Q_OS_WIN) m_widget->comboBoxFindPlace->clear(); @@ -246,7 +245,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->comboBoxFindPlace->setCurrentIndex(-1); #else #endif -*/ + // ************** @@ -271,7 +270,10 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - m_map->WPCreate(QPoint(1000,1000),10,"aaa"); + distBearing db; + db.distante=100; + db.bearing=0; + m_map->WPCreate(db,10,"aaa"); // ************** // create various context menu (mouse right click menu) actions @@ -470,11 +472,11 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); - /* + menu.addAction(findPlaceAct); menu.addSeparator(); - */ + QMenu safeArea("Safety Area definitions"); // menu.addAction(showSafeAreaAct); QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); @@ -551,7 +553,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) { case Normal_MapMode: // only show the waypoint stuff if not in 'magic waypoint' mode - /* + menu.addSeparator()->setText(tr("Waypoints")); menu.addAction(wayPointEditorAct); @@ -572,7 +574,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) if (m_waypoint_list.count() > 0) menu.addAction(clearWayPointsAct); // we have waypoints m_waypoint_list_mutex.unlock(); - */ + break; @@ -651,10 +653,6 @@ void OPMapGadgetWidget::updatePosition() return; QMutexLocker locker(&m_map_mutex); -// Pip I'm sorry, I know this was here with a purpose vvv -// from Pip: let you off :) - //if (!telemetry_connected) - // return; // ************* // get the current UAV details @@ -1435,12 +1433,12 @@ void OPMapGadgetWidget::createActions() copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard")); connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered())); - /* + findPlaceAct = new QAction(tr("&Find place"), this); findPlaceAct->setShortcut(tr("Ctrl+F")); findPlaceAct->setStatusTip(tr("Find a location")); connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered())); - */ + showCompassAct = new QAction(tr("Show compass"), this); showCompassAct->setStatusTip(tr("Show/Hide the compass")); @@ -1515,11 +1513,11 @@ void OPMapGadgetWidget::createActions() TODO: Waypoint support is disabled for v1.0 */ - /* + wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); wayPointEditorAct->setShortcut(tr("Ctrl+W")); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); - wayPointEditorAct->setEnabled(false); // temporary + wayPointEditorAct->setEnabled(true); // temporary connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); addWayPointAct = new QAction(tr("&Add waypoint"), this); @@ -1547,7 +1545,7 @@ void OPMapGadgetWidget::createActions() clearWayPointsAct->setShortcut(tr("Ctrl+C")); clearWayPointsAct->setStatusTip(tr("Clear waypoints")); connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); - */ + homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position")); @@ -1916,7 +1914,11 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) /** * TODO: unused for v1.0 **/ -/* +void OPMapGadgetWidget::onOpenWayPointEditorAct_triggered() +{ + waypoint_editor_dialog.show(); +} + void OPMapGadgetWidget::onAddWayPointAct_triggered() { if (!m_widget || !m_map) @@ -1930,7 +1932,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() // create a waypoint on the map at the last known mouse position t_waypoint *wp = new t_waypoint; wp->map_wp_item = NULL; - wp->coord = context_menu_lat_lon; + wp->coord = m_context_menu_lat_lon; wp->altitude = 0; wp->description = ""; wp->locked = false; @@ -1956,7 +1958,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() m_waypoint_list_mutex.unlock(); } -*/ + /** * Called when the user asks to edit a waypoint from the map @@ -1964,7 +1966,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() * TODO: should open an interface to edit waypoint properties, or * propagate the signal to a specific WP plugin (tbd). **/ -/* + void OPMapGadgetWidget::onEditWayPointAct_triggered() { if (!m_widget || !m_map) @@ -1976,16 +1978,16 @@ void OPMapGadgetWidget::onEditWayPointAct_triggered() if (!m_mouse_waypoint) return; - //waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); + waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); m_mouse_waypoint = NULL; } -*/ + /** * TODO: unused for v1.0 */ -/* + void OPMapGadgetWidget::onLockWayPointAct_triggered() { if (!m_widget || !m_map || !m_mouse_waypoint) @@ -2005,12 +2007,12 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() m_mouse_waypoint = NULL; } -*/ + /** * TODO: unused for v1.0 */ -/* + void OPMapGadgetWidget::onDeleteWayPointAct_triggered() { if (!m_widget || !m_map) @@ -2063,12 +2065,10 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() m_mouse_waypoint = NULL; } -*/ /** * TODO: No Waypoint support in v1.0 */ -/* void OPMapGadgetWidget::onClearWayPointsAct_triggered() { if (!m_widget || !m_map) @@ -2092,7 +2092,7 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() m_waypoint_list.clear(); } -*/ + void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() { @@ -2468,3 +2468,20 @@ void OPMapGadgetWidget::SetUavPic(QString UAVPic) { m_map->SetUavPic(UAVPic); } + +void OPMapGadgetWidget::on_tbFind_clicked() +{ + QPalette pal = m_widget->leFind->palette(); + + int result=m_map->SetCurrentPositionByKeywords(m_widget->leFind->text()); + if(result==core::GeoCoderStatusCode::G_GEO_SUCCESS) + { + pal.setColor( m_widget->leFind->backgroundRole(), Qt::green); + m_widget->leFind->setPalette(pal); + } + else + { + pal.setColor( m_widget->leFind->backgroundRole(), Qt::red); + m_widget->leFind->setPalette(pal); + } +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 8d374acdc..a8d0cd9c1 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -39,6 +39,8 @@ #include #include +#include "opmap_edit_waypoint_dialog.h" +#include "opmap_waypointeditor_dialog.h" #include "opmapcontrol/opmapcontrol.h" #include "opmap_overlay_widget.h" @@ -53,6 +55,7 @@ #include "uavobject.h" #include "objectpersistence.h" + // ****************************************************** namespace Ui @@ -142,21 +145,21 @@ private slots: * * Some are currently disabled for the v1.0 plugin version. */ -// void comboBoxFindPlace_returnPressed(); -// void on_toolButtonFindPlace_clicked(); + void comboBoxFindPlace_returnPressed(); + void on_toolButtonFindPlace_clicked(); void on_toolButtonZoomM_clicked(); void on_toolButtonZoomP_clicked(); void on_toolButtonMapHome_clicked(); void on_toolButtonMapUAV_clicked(); void on_toolButtonMapUAVheading_clicked(); void on_horizontalSliderZoom_sliderMoved(int position); -// void on_toolButtonAddWaypoint_clicked(); -// void on_treeViewWaypoints_clicked(QModelIndex index); -// void on_toolButtonHome_clicked(); -// void on_toolButtonNextWaypoint_clicked(); -// void on_toolButtonPrevWaypoint_clicked(); -// void on_toolButtonHoldPosition_clicked(); -// void on_toolButtonGo_clicked(); + void on_toolButtonAddWaypoint_clicked(); + void on_treeViewWaypoints_clicked(QModelIndex index); + void on_toolButtonHome_clicked(); + void on_toolButtonNextWaypoint_clicked(); + void on_toolButtonPrevWaypoint_clicked(); + void on_toolButtonHoldPosition_clicked(); + void on_toolButtonGo_clicked(); void on_toolButtonMagicWaypointMapMode_clicked(); void on_toolButtonNormalMapMode_clicked(); void on_toolButtonHomeWaypoint_clicked(); @@ -191,7 +194,7 @@ private slots: void onCopyMouseLatLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLonToClipAct_triggered(); -// void onFindPlaceAct_triggered(); + void onFindPlaceAct_triggered(); void onShowCompassAct_toggled(bool show); void onShowDiagnostics_toggled(bool show); void onShowUAVAct_toggled(bool show); @@ -206,14 +209,14 @@ private slots: void onGoUAVAct_triggered(); void onFollowUAVpositionAct_toggled(bool checked); void onFollowUAVheadingAct_toggled(bool checked); -/* + void onOpenWayPointEditorAct_triggered(); void onAddWayPointAct_triggered(); void onEditWayPointAct_triggered(); void onLockWayPointAct_triggered(); void onDeleteWayPointAct_triggered(); void onClearWayPointsAct_triggered(); -*/ + void onMapModeActGroup_triggered(QAction *action); void onZoomActGroup_triggered(QAction *action); void onHomeMagicWaypointAct_triggered(); @@ -225,6 +228,8 @@ private slots: void onUAVTrailDistanceActGroup_triggered(QAction *action); void onMaxUpdateRateActGroup_triggered(QAction *action); + void on_tbFind_clicked(); + private: // ***** @@ -261,9 +266,9 @@ private: UAVObjectManager *obm; UAVObjectUtilManager *obum; - //opmap_waypointeditor_dialog waypoint_editor_dialog; + opmap_waypointeditor_dialog waypoint_editor_dialog; - //opmap_edit_waypoint_dialog waypoint_edit_dialog; + opmap_edit_waypoint_dialog waypoint_edit_dialog; QStandardItemModel wayPoint_treeView_model; @@ -300,14 +305,14 @@ private: QAction *goUAVAct; QAction *followUAVpositionAct; QAction *followUAVheadingAct; - /* + QAction *wayPointEditorAct; QAction *addWayPointAct; QAction *editWayPointAct; QAction *lockWayPointAct; QAction *deleteWayPointAct; QAction *clearWayPointsAct; - */ + QAction *homeMagicWaypointAct; QAction *showSafeAreaAct; From f7f6ffcab1676fdb8a46d1eaaea856cbe84de64d Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 30 May 2012 16:19:36 +0100 Subject: [PATCH 009/116] GCS/MapLib - Work continues on the future pathplaner --- .../src/mapwidget/mapgraphicitem.cpp | 1 + .../src/mapwidget/mapgraphicitem.h | 3 + .../src/mapwidget/opmapwidget.cpp | 1 + .../opmapcontrol/src/mapwidget/opmapwidget.h | 1 + .../src/mapwidget/waypointitem.cpp | 65 +++++++-- .../opmapcontrol/src/mapwidget/waypointitem.h | 11 +- .../opmap/opmap_edit_waypoint_dialog.cpp | 39 ++++- .../opmap/opmap_edit_waypoint_dialog.h | 4 + .../opmap/opmap_edit_waypoint_dialog.ui | 133 ++++++++++++++---- .../src/plugins/opmap/opmapgadgetwidget.cpp | 9 +- .../src/plugins/opmap/opmapgadgetwidget.h | 5 +- 11 files changed, 216 insertions(+), 56 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index bd50c46da..2e098bc73 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -46,6 +46,7 @@ namespace mapcontrol connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); //resize(); } + void MapGraphicItem::start() { core->StartSystem(); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index c3c235617..3f96ffe8b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -40,8 +40,10 @@ #include #include "waypointitem.h" //#include "uavitem.h" + namespace mapcontrol { + class WayPointItem; class OPMapWidget; /** * @brief The main graphicsItem used on the widget, contains the map and map logic @@ -213,6 +215,7 @@ namespace mapcontrol * * @param zoom */ + void wpdoubleclicked(WayPointItem * wp); void zoomChanged(double zoomtotal,double zoomreal,double zoomdigi); }; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index b5c50f853..024d1dce2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -53,6 +53,7 @@ namespace mapcontrol connect(map->core,SIGNAL(OnTileLoadComplete()),this,SIGNAL(OnTileLoadComplete())); connect(map->core,SIGNAL(OnTileLoadStart()),this,SIGNAL(OnTileLoadStart())); connect(map->core,SIGNAL(OnTilesStillToLoad(int)),this,SIGNAL(OnTilesStillToLoad(int))); + connect(map,SIGNAL(wpdoubleclicked(WayPointItem*)),this,SIGNAL(OnWayPointDoubleClicked(WayPointItem*))); SetShowDiagnostics(showDiag); this->setMouseTracking(followmouse); SetShowCompass(true); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 4d3668e18..94710b057 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -478,6 +478,7 @@ namespace mapcontrol * @param number the number of tiles still in the queue */ void OnTilesStillToLoad(int number); + void OnWayPointDoubleClicked(WayPointItem * waypoint); public slots: /** * @brief Ripps the current selection to the DB diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 69a2287bb..871707ba4 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -53,9 +53,10 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu } if(myHome) - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); - + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + qDebug()<<"RELATIVE DISTANCE SET ON CTOR1"<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + qDebug()<<"RELATIVE DISTANCE SET ON CTOR2"< list=map->childItems(); foreach(QGraphicsItem * obj,list) @@ -98,7 +102,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(myHome) { connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); - coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distante,relativeCoord.bearing); + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); } myType=relative; text=0; @@ -112,9 +116,11 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + } - void WayPointItem::changeWPType(wptype type) + void WayPointItem::setWPType(wptype type) { myType=type; emit WPValuesChanged(this); @@ -135,6 +141,14 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(this->isSelected()) painter->drawRect(QRectF(-picture.width()/2,-picture.height(),picture.width()-1,picture.height()-1)); } + void WayPointItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + emit waypointdoubleclick(this); + } + } + void WayPointItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { if(event->button()==Qt::LeftButton) @@ -157,11 +171,17 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(event->button()==Qt::LeftButton) { - delete text; - delete textBG; - coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - if(myHome) - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); + if(text) + { + delete text; + text=NULL; + } + if(textBG) + { + delete textBG; + textBG=NULL; + } + isDragging=false; RefreshToolTip(); @@ -177,8 +197,11 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); if(myHome) - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distante,relativeCoord.bearing); - QString relativeCoord_str = QString::number(relativeCoord.distante) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; + { + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + qDebug()<<"RELATIVE DISTANCE SET ON MOUSEMOVEEVENT"<setText(coord_str+"\n"+relativeCoord_str); textBG->setRect(text->boundingRect()); @@ -194,6 +217,18 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu emit WPValuesChanged(this); this->update(); } + + void WayPointItem::setRelativeCoord(distBearing value) + { + relativeCoord=value; + if(myHome) + { + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + } + RefreshPos(); + RefreshToolTip(); + this->update(); + } void WayPointItem::SetCoord(const internals::PointLatLng &value) { coord=value; @@ -275,7 +310,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(myType==relative) { - coord=map->Projection()->translate(homepos,relativeCoord.distante,relativeCoord.bearing); + coord=map->Projection()->translate(homepos,relativeCoord.distance,relativeCoord.bearing); emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); @@ -332,7 +367,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu else type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distante) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); + QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str)); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 41db14f93..90c6c8029 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -39,7 +39,7 @@ namespace mapcontrol { struct distBearing { - double distante; + double distance; double bearing; }; class HomeItem; @@ -145,6 +145,8 @@ public: * @param value */ void SetAltitude(int const& value); + void setRelativeCoord(distBearing value); + distBearing getRelativeCoord(){return relativeCoord;} int type() const; QRectF boundingRect() const; void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, @@ -155,12 +157,13 @@ public: ~WayPointItem(); static int snumber; - void changeWPType(wptype type); + void setWPType(wptype type); + wptype WPType(){return myType;} protected: void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); void mousePressEvent ( QGraphicsSceneMouseEvent * event ); void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); - + void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); private: internals::PointLatLng coord;//coordinates of this WayPoint distBearing relativeCoord; @@ -220,7 +223,7 @@ signals: * @param waypoint a pointer to this WayPoint */ void WPValuesChanged(WayPointItem* waypoint); - + void waypointdoubleclick(WayPointItem* waypoint); }; } #endif // WAYPOINTITEM_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index c7cbb53b0..2c7d20761 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -36,8 +36,8 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent) : ui(new Ui::opmap_edit_waypoint_dialog) { ui->setupUi(this); - waypoint_item = NULL; + connect(ui->rbRelative,SIGNAL(toggled(bool)),this,SLOT(setupWidgets(bool))); } // destrutor @@ -87,6 +87,22 @@ void opmap_edit_waypoint_dialog::on_pushButtonRevert_clicked() saveSettings(); } +void opmap_edit_waypoint_dialog::setupWidgets(bool isRelative) +{ + ui->lbLong->setVisible(!isRelative); + ui->lbDegLong->setVisible(!isRelative); + ui->doubleSpinBoxLongitude->setVisible(!isRelative); + ui->lbLat->setVisible(!isRelative); + ui->lbDegLat->setVisible(!isRelative); + ui->doubleSpinBoxLatitude->setVisible(!isRelative); + ui->lbDistance->setVisible(isRelative); + ui->lbDistanceMeters->setVisible(isRelative); + ui->lbBearing->setVisible(isRelative); + ui->lbBearingDeg->setVisible(isRelative); + ui->spinBoxDistance->setVisible(isRelative); + ui->doubleSpinBoxBearing->setVisible(isRelative); +} + void opmap_edit_waypoint_dialog::on_pushButtonCancel_clicked() { waypoint_item = NULL; @@ -123,7 +139,14 @@ int opmap_edit_waypoint_dialog::saveSettings() waypoint_item->SetAltitude(altitude); waypoint_item->SetDescription(description); waypoint_item->setFlag(QGraphicsItem::ItemIsMovable, !locked); - + if(ui->rbAbsolute->isChecked()) + waypoint_item->setWPType(mapcontrol::WayPointItem::absolute); + else + waypoint_item->setWPType(mapcontrol::WayPointItem::relative); + mapcontrol::distBearing pt; + pt.distance=ui->spinBoxDistance->value(); + pt.bearing=ui->doubleSpinBoxBearing->value()/180*M_PI; + this->waypoint_item->setRelativeCoord(pt); // ******************** return 0; // all ok @@ -143,14 +166,22 @@ void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint original_coord = this->waypoint_item->Coord(); original_altitude = this->waypoint_item->Altitude(); original_description = this->waypoint_item->Description().simplified(); - + original_type=this->waypoint_item->WPType(); + original_distance=this->waypoint_item->getRelativeCoord().distance; + original_bearing=this->waypoint_item->getRelativeCoord().bearing*180/M_PI; ui->checkBoxLocked->setChecked(original_locked); ui->spinBoxNumber->setValue(original_number); ui->doubleSpinBoxLatitude->setValue(original_coord.Lat()); ui->doubleSpinBoxLongitude->setValue(original_coord.Lng()); ui->doubleSpinBoxAltitude->setValue(original_altitude); ui->lineEditDescription->setText(original_description); - + if(original_type==mapcontrol::WayPointItem::absolute) + ui->rbAbsolute->setChecked(true); + else + ui->rbRelative->setChecked(true); + ui->doubleSpinBoxBearing->setValue(original_bearing); + ui->spinBoxDistance->setValue(original_distance); + setupWidgets(ui->rbRelative->isChecked()); show(); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 062590fdd..45612253d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -61,6 +61,9 @@ private: internals::PointLatLng original_coord; double original_altitude; QString original_description; + double original_distance; + double original_bearing; + mapcontrol::WayPointItem::wptype original_type; mapcontrol::WayPointItem *waypoint_item; @@ -69,6 +72,7 @@ private: private slots: private slots: + void setupWidgets(bool isRelative); void on_pushButtonCancel_clicked(); void on_pushButtonRevert_clicked(); void on_pushButtonApply_clicked(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index 62d228782..84de38a2d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -9,28 +9,16 @@ 0 0 - 500 - 187 + 546 + 261 - + 0 0 - - - 500 - 187 - - - - - 500 - 187 - - OpenPilot GCS Edit Waypoint @@ -60,8 +48,8 @@ - - + + 0 @@ -76,8 +64,11 @@ - - + + + + true + 0 @@ -92,7 +83,7 @@ - + @@ -108,14 +99,14 @@ - + meters - + @@ -131,7 +122,7 @@ - + @@ -151,7 +142,7 @@ - + @@ -170,7 +161,7 @@ - + 7 @@ -183,7 +174,7 @@ - + -5000.000000000000000 @@ -193,20 +184,104 @@ - - + + degrees - + degrees + + + + + 0 + 0 + + + + Type + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Relative + + + + + + + Absolute + + + + + + + 999999999 + + + + + + + meters + + + + + + + degrees + + + + + + + Bearing + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 360.000000000000000 + + + + + + + + 0 + 0 + + + + Distance + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index be8d68fae..ee45341fa 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -264,14 +264,14 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); - + connect(m_map,SIGNAL(OnWayPointDoubleClicked(WayPointItem*)),this,SLOT(wpDoubleClickEvent(WayPointItem*))); m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position distBearing db; - db.distante=100; + db.distance=100; db.bearing=0; m_map->WPCreate(db,10,"aaa"); // ************** @@ -387,6 +387,11 @@ void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) QWidget::mouseMoveEvent(event); } +void OPMapGadgetWidget::wpDoubleClickEvent(WayPointItem *wp) +{ + m_mouse_waypoint = wp; + onEditWayPointAct_triggered(); +} void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) { // the user has right clicked on the map - create the pop-up context menu and display it diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index a8d0cd9c1..0d787204f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -119,7 +119,8 @@ public: void setCacheLocation(QString cacheLocation); void setMapMode(opMapModeType mode); void SetUavPic(QString UAVPic); - void setMaxUpdateRate(int update_rate); + void setMaxUpdateRate(int update_rate); + public slots: void homePositionUpdated(UAVObject *); @@ -131,8 +132,8 @@ protected: void mouseMoveEvent(QMouseEvent *event); void contextMenuEvent(QContextMenuEvent *event); void keyPressEvent(QKeyEvent* event); - private slots: + void wpDoubleClickEvent(WayPointItem *wp); void updatePosition(); void updateMousePos(); From 78db6d985343bdcf42e32d84ce3545ac1132450f Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 1 Jun 2012 15:28:35 +0100 Subject: [PATCH 010/116] GCS/MapLib-Added lines and circles between WPs overlay. --- .../opmapcontrol/src/mapwidget/mapwidget.pro | 104 +++++++++--------- .../src/mapwidget/opmapwidget.cpp | 10 ++ .../opmapcontrol/src/mapwidget/opmapwidget.h | 4 + .../src/mapwidget/waypointcircle.cpp | 97 ++++++++++++++++ .../src/mapwidget/waypointcircle.h | 67 +++++++++++ .../src/mapwidget/waypointitem.cpp | 11 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 8 ++ .../src/mapwidget/waypointline.cpp | 89 +++++++++++++++ .../opmapcontrol/src/mapwidget/waypointline.h | 64 +++++++++++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 13 ++- .../uavobjectwidgetutils/mixercurveline.h | 2 +- .../uavobjectwidgetutils/mixercurvepoint.h | 2 +- 12 files changed, 414 insertions(+), 57 deletions(-) create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapwidget.pro b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapwidget.pro index b2098fb78..93627ddc5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapwidget.pro +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapwidget.pro @@ -1,50 +1,54 @@ -TEMPLATE = lib -TARGET = opmapwidget -DEFINES += OPMAPWIDGET_LIBRARY -include(../../../../openpilotgcslibrary.pri) - -# DESTDIR = ../build -SOURCES += mapgraphicitem.cpp \ - opmapwidget.cpp \ - configuration.cpp \ - waypointitem.cpp \ - uavitem.cpp \ - gpsitem.cpp \ - trailitem.cpp \ - homeitem.cpp \ - mapripform.cpp \ - mapripper.cpp \ - traillineitem.cpp - -LIBS += -L../build \ - -lcore \ - -linternals \ - -lcore - -# order of linking matters -include(../../../utils/utils.pri) - -POST_TARGETDEPS += ../build/libcore.a -POST_TARGETDEPS += ../build/libinternals.a - -HEADERS += mapgraphicitem.h \ - opmapwidget.h \ - configuration.h \ - waypointitem.h \ - uavitem.h \ - gpsitem.h \ - uavmapfollowtype.h \ - uavtrailtype.h \ - trailitem.h \ - homeitem.h \ - mapripform.h \ - mapripper.h \ - traillineitem.h -QT += opengl -QT += network -QT += sql -QT += svg -RESOURCES += mapresources.qrc - -FORMS += \ - mapripform.ui +TEMPLATE = lib +TARGET = opmapwidget +DEFINES += OPMAPWIDGET_LIBRARY +include(../../../../openpilotgcslibrary.pri) + +# DESTDIR = ../build +SOURCES += mapgraphicitem.cpp \ + opmapwidget.cpp \ + configuration.cpp \ + waypointitem.cpp \ + uavitem.cpp \ + gpsitem.cpp \ + trailitem.cpp \ + homeitem.cpp \ + mapripform.cpp \ + mapripper.cpp \ + traillineitem.cpp \ + waypointline.cpp \ + waypointcircle.cpp + +LIBS += -L../build \ + -lcore \ + -linternals \ + -lcore + +# order of linking matters +include(../../../utils/utils.pri) + +POST_TARGETDEPS += ../build/libcore.a +POST_TARGETDEPS += ../build/libinternals.a + +HEADERS += mapgraphicitem.h \ + opmapwidget.h \ + configuration.h \ + waypointitem.h \ + uavitem.h \ + gpsitem.h \ + uavmapfollowtype.h \ + uavtrailtype.h \ + trailitem.h \ + homeitem.h \ + mapripform.h \ + mapripper.h \ + traillineitem.h \ + waypointline.h \ + waypointcircle.h +QT += opengl +QT += network +QT += sql +QT += svg +RESOURCES += mapresources.qrc + +FORMS += \ + mapripform.ui diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 024d1dce2..fa10a26dd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -42,6 +42,7 @@ namespace mapcontrol this->setScene(&mscene); Home=new HomeItem(map,this); Home->setParentItem(map); + Home->setZValue(-1); setStyleSheet("QToolTip {font-size:8pt; color:blue;opacity: 223; padding:2px; border-width:2px; border-style:solid; border-color: rgb(170, 170, 127);border-radius:4px }"); this->adjustSize(); connect(map,SIGNAL(zoomChanged(double,double,double)),this,SIGNAL(zoomChanged(double,double,double))); @@ -103,6 +104,15 @@ namespace mapcontrol } + + WayPointLine * OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to) + { + return new WayPointLine(from,to,map); + } + WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *from, WayPointItem *to, bool clockwise) + { + return new WayPointCircle(from,to,clockwise,map); + } void OPMapWidget::SetShowUAV(const bool &value) { if(value && UAV==0) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 94710b057..2d0604f3d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -41,6 +41,8 @@ #include "gpsitem.h" #include "homeitem.h" #include "mapripper.h" +#include "waypointline.h" +#include "waypointcircle.h" namespace mapcontrol { class UAVItem; @@ -358,6 +360,8 @@ namespace mapcontrol bool ShowHome()const{return showhome;} void SetShowDiagnostics(bool const& value); void SetUavPic(QString UAVPic); + WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to); + WayPointCircle *WPCircleCreate(WayPointItem *from, WayPointItem *to,bool clockwise); private: internals::Core *core; MapGraphicItem *map; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp new file mode 100644 index 000000000..f3868a17f --- /dev/null +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -0,0 +1,97 @@ +/** +****************************************************************************** +* +* @file waypointcircle.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief A graphicsItem representing a circle connecting 2 waypoints +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "waypointcircle.h" +#include + +const qreal Pi = 3.14; + +namespace mapcontrol +{ +WayPointCircle::WayPointCircle(WayPointItem *from, WayPointItem *to,bool clockwise, MapGraphicItem *map,QColor color):source(from), + destination(to),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) +{ + QLineF line(from->pos(),to->pos()); + this->setRect(from->pos().x(),from->pos().y(),2*line.length(),2*line.length()); + connect(source,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(destination,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(source,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(destination,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); +} +int WayPointCircle::type() const +{ + // Enable the use of qgraphicsitem_cast with this item. + return Type; +} +QPainterPath WayPointCircle::shape() const +{ + QPainterPath path = QGraphicsEllipseItem::shape(); + path.addPolygon(arrowHead); + return path; +} +void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) +{ + QLineF line(destination->pos(),source->pos()); + QPen myPen = pen(); + myPen.setColor(myColor); + qreal arrowSize = 10; + painter->setPen(myPen); + QBrush brush=painter->brush(); + painter->setBrush(myColor); + + double angle = ::acos(line.dx() / line.length()); + angle=angle+90*2*Pi/360; + if(myClockWise) + angle+=Pi; + if (line.dy() >= 0) + angle = (Pi) - angle; + + QPointF arrowP1 = line.p1() + QPointF(sin(angle + Pi / 3) * arrowSize, + cos(angle + Pi / 3) * arrowSize); + QPointF arrowP2 = line.p1() + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, + cos(angle + Pi - Pi / 3) * arrowSize); + + arrowHead.clear(); + arrowHead << line.p1() << arrowP1 << arrowP2; + painter->drawPolygon(arrowHead); + painter->translate(-line.length(),-line.length()); + painter->setBrush(brush); + painter->drawEllipse(this->rect()); + +} + +void WayPointCircle::refreshLocations() +{ + QLineF line(source->pos(),destination->pos()); + this->setRect(source->pos().x(),source->pos().y(),2*line.length(),2*line.length()); +} + +void WayPointCircle::waypointdeleted() +{ + this->deleteLater(); +} + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h new file mode 100644 index 000000000..4500a106d --- /dev/null +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h @@ -0,0 +1,67 @@ +/** +****************************************************************************** +* +* @file waypointcircle.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief A graphicsItem representing a circle connecting 2 waypoints +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef WAYPOINTCIRCLE_H +#define WAYPOINTCIRCLE_H +#include +#include +#include +#include "../internals/pointlatlng.h" +#include "mapgraphicitem.h" +#include "waypointitem.h" +#include +#include + +namespace mapcontrol +{ + +class WayPointCircle:public QObject,public QGraphicsEllipseItem +{ + Q_OBJECT + Q_INTERFACES(QGraphicsItem) +public: + enum { Type = UserType + 9 }; + WayPointCircle(WayPointItem * from, WayPointItem * to,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); + int type() const; + QPainterPath shape() const; + void setColor(const QColor &color) + { myColor = color; } +private: + WayPointItem * source; + WayPointItem * destination; + MapGraphicItem * my_map; + QPolygonF arrowHead; + QColor myColor; + bool myClockWise; +protected: + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); +public slots: + void refreshLocations(); + void waypointdeleted(); +}; +} + +#endif // WAYPOINTCIRCLE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 871707ba4..318f1e05f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -42,7 +42,6 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu SetShowNumber(shownumber); RefreshToolTip(); RefreshPos(); - myHome=NULL; QList list=map->childItems(); foreach(QGraphicsItem * obj,list) @@ -184,7 +183,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu isDragging=false; RefreshToolTip(); - + emit localPositionChanged(this->pos()); emit WPValuesChanged(this); } QGraphicsItem::mouseReleaseEvent(event); @@ -204,7 +203,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu QString relativeCoord_str = QString::number(relativeCoord.distance) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; text->setText(coord_str+"\n"+relativeCoord_str); textBG->setRect(text->boundingRect()); - + emit localPositionChanged(this->pos()); emit WPValuesChanged(this); } QGraphicsItem::mouseMoveEvent(event); @@ -232,6 +231,8 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu void WayPointItem::SetCoord(const internals::PointLatLng &value) { coord=value; + if(myHome) + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); @@ -352,12 +353,14 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu WayPointItem::~WayPointItem() { + emit aboutToBeDeleted(this); --WayPointItem::snumber; } void WayPointItem::RefreshPos() { core::Point point=map->FromLatLngToLocal(coord); this->setPos(point.X(),point.Y()); + emit localPositionChanged(this->pos()); } void WayPointItem::RefreshToolTip() { @@ -368,7 +371,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str)); + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7\n%8").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); } int WayPointItem::snumber=0; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 90c6c8029..dd25d51ed 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -154,6 +154,10 @@ public: void RefreshPos(); void RefreshToolTip(); QPixmap picture; + QVariant customData(){return myCustomData;} + void setCustomData(QVariant arg){myCustomData=arg;} + QString customString(){return myCustomString;} + void setCustomString(QString arg){myCustomString=arg;} ~WayPointItem(); static int snumber; @@ -183,6 +187,8 @@ private: QTransform transf; HomeItem * myHome; wptype myType; + QVariant myCustomData; + QString myCustomString; public slots: /** @@ -224,6 +230,8 @@ signals: */ void WPValuesChanged(WayPointItem* waypoint); void waypointdoubleclick(WayPointItem* waypoint); + void localPositionChanged(QPointF point); + void aboutToBeDeleted(WayPointItem *); }; } #endif // WAYPOINTITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp new file mode 100644 index 000000000..4044e56a7 --- /dev/null +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -0,0 +1,89 @@ +/** +****************************************************************************** +* +* @file waypointline.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief A graphicsItem representing a line connecting 2 waypoints +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "waypointline.h" +#include + +const qreal Pi = 3.14; + +namespace mapcontrol +{ +WayPointLine::WayPointLine(WayPointItem *from, WayPointItem *to, MapGraphicItem *map,QColor color):source(from), + destination(to),my_map(map),QGraphicsLineItem(map),myColor(color) +{ + this->setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); + connect(source,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(destination,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(source,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(destination,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); +} +int WayPointLine::type() const +{ + // Enable the use of qgraphicsitem_cast with this item. + return Type; +} +QPainterPath WayPointLine::shape() const +{ + QPainterPath path = QGraphicsLineItem::shape(); + path.addPolygon(arrowHead); + return path; +} +void WayPointLine::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) +{ + + QPen myPen = pen(); + myPen.setColor(myColor); + qreal arrowSize = 10; + painter->setPen(myPen); + painter->setBrush(myColor); + + double angle = ::acos(line().dx() / line().length()); + if (line().dy() >= 0) + angle = (Pi * 2) - angle; + + QPointF arrowP1 = line().p1() + QPointF(sin(angle + Pi / 3) * arrowSize, + cos(angle + Pi / 3) * arrowSize); + QPointF arrowP2 = line().p1() + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, + cos(angle + Pi - Pi / 3) * arrowSize); + + arrowHead.clear(); + arrowHead << line().p1() << arrowP1 << arrowP2; +//! [6] //! [7] + painter->drawLine(line()); + painter->drawPolygon(arrowHead); +} + +void WayPointLine::refreshLocations() +{ + this->setLine(destination->pos().x(),destination->pos().y(),source->pos().x(),source->pos().y()); +} + +void WayPointLine::waypointdeleted() +{ + this->deleteLater(); +} + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h new file mode 100644 index 000000000..420d64183 --- /dev/null +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h @@ -0,0 +1,64 @@ +/** +****************************************************************************** +* +* @file waypointline.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief A graphicsItem representing a line connecting 2 waypoints +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef WAYPOINTLINE_H +#define WAYPOINTLINE_H +#include +#include +#include +#include "../internals/pointlatlng.h" +#include "mapgraphicitem.h" +#include "waypointitem.h" +#include +#include + +namespace mapcontrol +{ +class WayPointLine:public QObject,public QGraphicsLineItem +{ + Q_OBJECT + Q_INTERFACES(QGraphicsItem) +public: + enum { Type = UserType + 8 }; + WayPointLine(WayPointItem * from, WayPointItem * to,MapGraphicItem * map,QColor color=Qt::green); + int type() const; + QPainterPath shape() const; + void setColor(const QColor &color) + { myColor = color; } +private: + WayPointItem * source; + WayPointItem * destination; + MapGraphicItem * my_map; + QPolygonF arrowHead; + QColor myColor; +protected: + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); +public slots: + void refreshLocations(); + void waypointdeleted(); +}; +} +#endif // WAYPOINTLINE_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index ee45341fa..b128c9582 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -273,7 +273,18 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) distBearing db; db.distance=100; db.bearing=0; - m_map->WPCreate(db,10,"aaa"); + WayPointItem * p1=m_map->WPCreate(db,10,"aaa"); + + db.distance=100; + db.bearing=45; + WayPointItem * p2=m_map->WPCreate(db,10,"bbb"); + m_map->WPCircleCreate(p2,p1,true); + t_waypoint *wp = new t_waypoint; + wp->map_wp_item=p1; + m_waypoint_list.append(wp); + wp=new t_waypoint; + wp->map_wp_item=p2; + m_waypoint_list.append(wp); // ************** // create various context menu (mouse right click menu) actions diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurveline.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurveline.h index 80fb50e0c..417f5b1ca 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurveline.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurveline.h @@ -51,7 +51,7 @@ public: void adjust(); - enum { Type = UserType + 2 }; + enum { Type = UserType + 12 }; int type() const { return Type; } protected: diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h index 987875e32..986d248a5 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/mixercurvepoint.h @@ -45,7 +45,7 @@ public: void addEdge(Edge *edge); QList edges() const; - enum { Type = UserType + 1 }; + enum { Type = UserType + 10 }; int type() const { return Type; } void verticalMove(bool flag); From 3106917703baa1583d3b52fa19c350595e5a9f18 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 1 Jun 2012 19:14:50 +0100 Subject: [PATCH 011/116] GCS/MapLib - added some UAVOs from Corvus pathplanner branch --- shared/uavobjectdefinition/pathaction.xml | 30 +++++++++++++++++++ shared/uavobjectdefinition/waypoint.xml | 12 ++++++++ shared/uavobjectdefinition/waypointactive.xml | 10 +++++++ 3 files changed, 52 insertions(+) create mode 100644 shared/uavobjectdefinition/pathaction.xml create mode 100644 shared/uavobjectdefinition/waypoint.xml create mode 100644 shared/uavobjectdefinition/waypointactive.xml diff --git a/shared/uavobjectdefinition/pathaction.xml b/shared/uavobjectdefinition/pathaction.xml new file mode 100644 index 000000000..8261c170c --- /dev/null +++ b/shared/uavobjectdefinition/pathaction.xml @@ -0,0 +1,30 @@ + + + A waypoint command the pathplanner is to use at a certain waypoint + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/waypoint.xml b/shared/uavobjectdefinition/waypoint.xml new file mode 100644 index 000000000..45107e7d4 --- /dev/null +++ b/shared/uavobjectdefinition/waypoint.xml @@ -0,0 +1,12 @@ + + + A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module + + + + + + + + + diff --git a/shared/uavobjectdefinition/waypointactive.xml b/shared/uavobjectdefinition/waypointactive.xml new file mode 100644 index 000000000..b0e2f3785 --- /dev/null +++ b/shared/uavobjectdefinition/waypointactive.xml @@ -0,0 +1,10 @@ + + + Indicates the currently active waypoint + + + + + + + From 40cfe0f4d9c4136380ea8911e7dd5a914463c192 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 1 Jun 2012 19:46:04 +0100 Subject: [PATCH 012/116] GCS/MapLib - Cleaned unused functions, added new UAVOs to objects.pro --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 10 ---------- .../src/plugins/opmap/opmapgadgetwidget.h | 10 ---------- .../src/plugins/uavobjects/uavobjects.pro | 11 ++++++++--- 3 files changed, 8 insertions(+), 23 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index b128c9582..77d2aea86 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -488,9 +488,6 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) menu.addSeparator(); - - menu.addAction(findPlaceAct); - menu.addSeparator(); QMenu safeArea("Safety Area definitions"); @@ -1449,13 +1446,6 @@ void OPMapGadgetWidget::createActions() copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard")); connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered())); - - findPlaceAct = new QAction(tr("&Find place"), this); - findPlaceAct->setShortcut(tr("Ctrl+F")); - findPlaceAct->setStatusTip(tr("Find a location")); - connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered())); - - showCompassAct = new QAction(tr("Show compass"), this); showCompassAct->setStatusTip(tr("Show/Hide the compass")); showCompassAct->setCheckable(true); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 0d787204f..669393743 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -147,20 +147,12 @@ private slots: * Some are currently disabled for the v1.0 plugin version. */ void comboBoxFindPlace_returnPressed(); - void on_toolButtonFindPlace_clicked(); void on_toolButtonZoomM_clicked(); void on_toolButtonZoomP_clicked(); void on_toolButtonMapHome_clicked(); void on_toolButtonMapUAV_clicked(); void on_toolButtonMapUAVheading_clicked(); void on_horizontalSliderZoom_sliderMoved(int position); - void on_toolButtonAddWaypoint_clicked(); - void on_treeViewWaypoints_clicked(QModelIndex index); - void on_toolButtonHome_clicked(); - void on_toolButtonNextWaypoint_clicked(); - void on_toolButtonPrevWaypoint_clicked(); - void on_toolButtonHoldPosition_clicked(); - void on_toolButtonGo_clicked(); void on_toolButtonMagicWaypointMapMode_clicked(); void on_toolButtonNormalMapMode_clicked(); void on_toolButtonHomeWaypoint_clicked(); @@ -195,7 +187,6 @@ private slots: void onCopyMouseLatLonToClipAct_triggered(); void onCopyMouseLatToClipAct_triggered(); void onCopyMouseLonToClipAct_triggered(); - void onFindPlaceAct_triggered(); void onShowCompassAct_toggled(bool show); void onShowDiagnostics_toggled(bool show); void onShowUAVAct_toggled(bool show); @@ -293,7 +284,6 @@ private: QAction *copyMouseLatLonToClipAct; QAction *copyMouseLatToClipAct; QAction *copyMouseLonToClipAct; - QAction *findPlaceAct; QAction *showCompassAct; QAction *showDiagnostics; QAction *showHomeAct; diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 8cdcb569b..c88bfc034 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -74,8 +74,10 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/attitudesettings.h \ $$UAVOBJECT_SYNTHETICS/txpidsettings.h \ $$UAVOBJECT_SYNTHETICS/cameradesired.h \ - $$UAVOBJECT_SYNTHETICS/faultsettings.h - + $$UAVOBJECT_SYNTHETICS/faultsettings.h \ + $$UAVOBJECT_SYNTHETICS/waypoint.h \ + $$UAVOBJECT_SYNTHETICS/waypointactive.h \ + $$UAVOBJECT_SYNTHETICS/pathaction.h SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/ahrsstatus.cpp \ $$UAVOBJECT_SYNTHETICS/ahrscalibration.cpp \ @@ -128,4 +130,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \ $$UAVOBJECT_SYNTHETICS/txpidsettings.cpp \ $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ - $$UAVOBJECT_SYNTHETICS/faultsettings.cpp + $$UAVOBJECT_SYNTHETICS/faultsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/waypoint.cpp \ + $$UAVOBJECT_SYNTHETICS/waypointactive.cpp \ + $$UAVOBJECT_SYNTHETICS/pathaction.cpp From 3b8ca57eef490ff1c0fae066ac96a6b87b07e4e8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 1 Jun 2012 22:13:29 +0100 Subject: [PATCH 013/116] GCS/MapLib - added pathplanmanager class --- .../opmapcontrol/src/mapwidget/opmapwidget.h | 1 + .../openpilotgcs/src/plugins/opmap/opmap.pro | 95 ++++++++++--------- .../opmap/opmap_edit_waypoint_dialog.h | 2 + .../src/plugins/opmap/opmapgadgetwidget.h | 1 - .../src/plugins/opmap/pathplanmanager.cpp | 60 ++++++++++++ .../src/plugins/opmap/pathplanmanager.h | 65 +++++++++++++ .../src/plugins/opmap/pathplanmanager.ui | 21 ++++ 7 files changed, 198 insertions(+), 47 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 2d0604f3d..6438131be 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -43,6 +43,7 @@ #include "mapripper.h" #include "waypointline.h" #include "waypointcircle.h" +#include "waypointitem.h" namespace mapcontrol { class UAVItem; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index caab7a52f..61b200a97 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -1,46 +1,49 @@ -TEMPLATE = lib -TARGET = OPMapGadget - -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(../../libs/opmapcontrol/opmapcontrol.pri) -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/uavobjectutil/uavobjectutil.pri) -include(../../plugins/uavtalk/uavtalk.pri) -include(../../libs/utils/utils.pri) - -HEADERS += opmapplugin.h \ - opmapgadgetoptionspage.h \ - opmapgadgetfactory.h \ - opmapgadgetconfiguration.h \ - opmapgadget.h \ - opmapgadgetwidget.h \ - opmap_waypointeditor_dialog.h \ - opmap_edit_waypoint_dialog.h \ - opmap_zoom_slider_widget.h \ - opmap_statusbar_widget.h \ - opmap_overlay_widget.h - -SOURCES += opmapplugin.cpp \ - opmapgadgetwidget.cpp \ - opmapgadgetoptionspage.cpp \ - opmapgadgetfactory.cpp \ - opmapgadgetconfiguration.cpp \ - opmapgadget.cpp \ - opmap_waypointeditor_dialog.cpp \ - opmap_edit_waypoint_dialog.cpp \ - opmap_zoom_slider_widget.cpp \ - opmap_statusbar_widget.cpp \ - opmap_overlay_widget.cpp - -OTHER_FILES += OPMapGadget.pluginspec - -FORMS += opmapgadgetoptionspage.ui \ - opmap_widget.ui \ - opmap_waypointeditor_dialog.ui \ - opmap_edit_waypoint_dialog.ui \ - opmap_zoom_slider_widget.ui \ - opmap_statusbar_widget.ui \ - opmap_overlay_widget.ui - -RESOURCES += opmap.qrc +TEMPLATE = lib +TARGET = OPMapGadget + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../libs/opmapcontrol/opmapcontrol.pri) +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) +include(../../plugins/uavtalk/uavtalk.pri) +include(../../libs/utils/utils.pri) + +HEADERS += opmapplugin.h \ + opmapgadgetoptionspage.h \ + opmapgadgetfactory.h \ + opmapgadgetconfiguration.h \ + opmapgadget.h \ + opmapgadgetwidget.h \ + opmap_waypointeditor_dialog.h \ + opmap_edit_waypoint_dialog.h \ + opmap_zoom_slider_widget.h \ + opmap_statusbar_widget.h \ + opmap_overlay_widget.h \ + pathplanmanager.h + +SOURCES += opmapplugin.cpp \ + opmapgadgetwidget.cpp \ + opmapgadgetoptionspage.cpp \ + opmapgadgetfactory.cpp \ + opmapgadgetconfiguration.cpp \ + opmapgadget.cpp \ + opmap_waypointeditor_dialog.cpp \ + opmap_edit_waypoint_dialog.cpp \ + opmap_zoom_slider_widget.cpp \ + opmap_statusbar_widget.cpp \ + opmap_overlay_widget.cpp \ + pathplanmanager.cpp + +OTHER_FILES += OPMapGadget.pluginspec + +FORMS += opmapgadgetoptionspage.ui \ + opmap_widget.ui \ + opmap_waypointeditor_dialog.ui \ + opmap_edit_waypoint_dialog.ui \ + opmap_zoom_slider_widget.ui \ + opmap_statusbar_widget.ui \ + opmap_overlay_widget.ui \ + pathplanmanager.ui + +RESOURCES += opmap.qrc diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 45612253d..b6fde4828 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -63,6 +63,8 @@ private: QString original_description; double original_distance; double original_bearing; + + mapcontrol::WayPointItem::wptype original_type; mapcontrol::WayPointItem *waypoint_item; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 669393743..e787f1cf7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -146,7 +146,6 @@ private slots: * * Some are currently disabled for the v1.0 plugin version. */ - void comboBoxFindPlace_returnPressed(); void on_toolButtonZoomM_clicked(); void on_toolButtonZoomP_clicked(); void on_toolButtonMapHome_clicked(); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp new file mode 100644 index 000000000..cc60dcc5b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp @@ -0,0 +1,60 @@ +/** + ****************************************************************************** + * + * @file pathplanmanager.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "pathplanmanager.h" +#include "ui_pathplanmanager.h" + +pathPlanManager::pathPlanManager(QWidget *parent,OPMapWidget *map): + QWidget(parent),myMap(map), + ui(new Ui::pathPlanManager) +{ + ui->setupUi(this); + connect(myMap,SIGNAL(WPDeleted(int)),this,SLOT(on_WPDeleted(int))); + connect(myMap,SIGNAL(WPInserted(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); + connect(myMap,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SLOT(on_WPNumberChanged(int,int,WayPointItem*))); + connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(on_WPValuesChanged(WayPointItem*))); + +} + +pathPlanManager::~pathPlanManager() +{ + delete ui; +} +void pathPlanManager::on_WPDeleted(int wp_number) +{ +} + +void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) +{ +} + +void pathPlanManager::on_WPNumberChanged(int oldNumber, int newNumber, WayPointItem * wp) +{ +} + +void pathPlanManager::on_WPValuesChanged(WayPointItem * wp) +{ +} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h new file mode 100644 index 000000000..aa318f743 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h @@ -0,0 +1,65 @@ +/** + ****************************************************************************** + * + * @file pathplanmanager.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PATHPLANMANAGER_H +#define PATHPLANMANAGER_H + +#include +#include "opmapcontrol/opmapcontrol.h" + +namespace Ui { +class pathPlanManager; +} +using namespace mapcontrol; +class pathPlanManager : public QWidget +{ + Q_OBJECT + struct customData + { + float velocity; + int mode; + float mode_params[4]; + int condition; + float condition_params[4]; + int command; + int jumpdestination; + int errordestination; + }; +public: + explicit pathPlanManager(QWidget *parent,OPMapWidget * map); + ~pathPlanManager(); +private slots: + void on_WPDeleted(int); + void on_WPInserted(int,WayPointItem*); + void on_WPNumberChanged(int,int,WayPointItem*); + void on_WPValuesChanged(WayPointItem*); +private: + Ui::pathPlanManager *ui; + OPMapWidget * myMap; +}; + +#endif // PATHPLANMANAGER_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui new file mode 100644 index 000000000..c8fbf92cb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui @@ -0,0 +1,21 @@ + + + + + pathPlanManager + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + From d0e012cbdbd3fe6557c9c7d51537b7fe017b9974 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 2 Jun 2012 22:32:56 +0100 Subject: [PATCH 014/116] GCS/MapLib - Added path plan manager. --- .../src/mapwidget/opmapwidget.cpp | 52 +++++++++++-- .../opmapcontrol/src/mapwidget/opmapwidget.h | 10 ++- .../src/mapwidget/waypointcircle.cpp | 55 +++++++++----- .../src/mapwidget/waypointcircle.h | 7 +- .../src/mapwidget/waypointitem.cpp | 33 +++------ .../opmapcontrol/src/mapwidget/waypointitem.h | 2 +- .../src/mapwidget/waypointline.cpp | 19 +++-- .../opmapcontrol/src/mapwidget/waypointline.h | 5 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 13 +++- .../src/plugins/opmap/opmapgadgetwidget.h | 2 +- .../src/plugins/opmap/pathplanmanager.cpp | 73 +++++++++++++++++-- .../src/plugins/opmap/pathplanmanager.h | 25 +++++-- 12 files changed, 217 insertions(+), 79 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index fa10a26dd..7dd2ef600 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -101,17 +101,32 @@ namespace mapcontrol UAV->SetUavPic(UAVPic); if(GPS!=0) GPS->SetUavPic(UAVPic); - - } WayPointLine * OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to) { + if(!from|!to) + return NULL; return new WayPointLine(from,to,map); } - WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *from, WayPointItem *to, bool clockwise) + WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to) { - return new WayPointCircle(from,to,clockwise,map); + if(!from|!to) + return NULL; + return new WayPointLine(from,to,map); + } + WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise) + { + if(!center|!radius) + return NULL; + return new WayPointCircle(center,radius,clockwise,map); + } + + WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise) + { + if(!center|!radius) + return NULL; + return new WayPointCircle(center,radius,clockwise,map); } void OPMapWidget::SetShowUAV(const bool &value) { @@ -201,18 +216,24 @@ namespace mapcontrol WayPointItem* item=new WayPointItem(this->CurrentPosition(),0,map); ConnectWP(item); item->setParentItem(map); + int position=item->Number(); + emit WPCreated(position,item); return item; } void OPMapWidget::WPCreate(WayPointItem* item) { ConnectWP(item); item->setParentItem(map); + int position=item->Number(); + emit WPCreated(position,item); } WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude) { WayPointItem* item=new WayPointItem(coord,altitude,map); ConnectWP(item); item->setParentItem(map); + int position=item->Number(); + emit WPCreated(position,item); return item; } WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude, QString const& description) @@ -220,6 +241,8 @@ namespace mapcontrol WayPointItem* item=new WayPointItem(coord,altitude,description,map); ConnectWP(item); item->setParentItem(map); + int position=item->Number(); + emit WPCreated(position,item); return item; } WayPointItem* OPMapWidget::WPCreate(const distBearing &relativeCoord, const int &altitude, const QString &description) @@ -227,6 +250,8 @@ namespace mapcontrol WayPointItem* item=new WayPointItem(relativeCoord,altitude,description,map); ConnectWP(item); item->setParentItem(map); + int position=item->Number(); + emit WPCreated(position,item); return item; } WayPointItem* OPMapWidget::WPInsert(const int &position) @@ -266,7 +291,7 @@ namespace mapcontrol } void OPMapWidget::WPDelete(WayPointItem *item) { - emit WPDeleted(item->Number()); + emit WPDeleted(item->Number(),item); delete item; } void OPMapWidget::WPDeleteAll() @@ -278,6 +303,21 @@ namespace mapcontrol delete w; } } + void OPMapWidget::deleteAllOverlays() + { + foreach(QGraphicsItem* i,map->childItems()) + { + WayPointLine* w=qgraphicsitem_cast(i); + if(w) + delete w; + else + { + WayPointCircle* ww=qgraphicsitem_cast(i); + if(ww) + delete ww; + } + } + } QList OPMapWidget::WPSelected() { QList list; @@ -300,7 +340,7 @@ namespace mapcontrol connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*))); connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*))); connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*))); - connect(this,SIGNAL(WPDeleted(int)),item,SLOT(WPDeleted(int))); + connect(this,SIGNAL(WPDeleted(int,WayPointItem*)),item,SLOT(WPDeleted(int,WayPointItem*))); } void OPMapWidget::diagRefresh() { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 6438131be..67d4e08fb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -362,7 +362,10 @@ namespace mapcontrol void SetShowDiagnostics(bool const& value); void SetUavPic(QString UAVPic); WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to); - WayPointCircle *WPCircleCreate(WayPointItem *from, WayPointItem *to,bool clockwise); + WayPointLine * WPLineCreate(HomeItem *from,WayPointItem *to); + WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise); + WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise); + void deleteAllOverlays(); private: internals::Core *core; MapGraphicItem *map; @@ -412,6 +415,9 @@ namespace mapcontrol * @param waypoint WayPoint inserted */ void WPReached(WayPointItem* waypoint); + + void WPCreated(int const& number,WayPointItem* waypoint); + /** * @brief Fires when a new WayPoint is inserted * @@ -424,7 +430,7 @@ namespace mapcontrol * * @param number number of the deleted WayPoint */ - void WPDeleted(int const& number); + void WPDeleted(int const& number,WayPointItem* waypoint); /** * @brief Fires When a WayPoint is Reached * diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index f3868a17f..b61e073db 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -26,21 +26,28 @@ */ #include "waypointcircle.h" #include - +#include "homeitem.h" const qreal Pi = 3.14; namespace mapcontrol { -WayPointCircle::WayPointCircle(WayPointItem *from, WayPointItem *to,bool clockwise, MapGraphicItem *map,QColor color):source(from), - destination(to),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) +WayPointCircle::WayPointCircle(WayPointItem *center, WayPointItem *radius,bool clockwise, MapGraphicItem *map,QColor color):my_center(center), + my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) { - QLineF line(from->pos(),to->pos()); - this->setRect(from->pos().x(),from->pos().y(),2*line.length(),2*line.length()); - connect(source,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(destination,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(source,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); - connect(destination,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(center,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(radius,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(center,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(radius,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); } + +WayPointCircle::WayPointCircle(HomeItem *center, WayPointItem *radius, bool clockwise, MapGraphicItem *map, QColor color):my_center(center), + my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) +{ + connect(center,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); + connect(radius,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(radius,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); +} + int WayPointCircle::type() const { // Enable the use of qgraphicsitem_cast with this item. @@ -54,28 +61,40 @@ QPainterPath WayPointCircle::shape() const } void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) { - QLineF line(destination->pos(),source->pos()); + QPointF p1; + QPointF p2; + p1=my_center->pos(); + p2=my_center->pos(); + QLineF line(my_radius->pos(),my_center->pos()); + p1.ry()=p1.ry()+line.length(); + p2.ry()=p2.ry()-line.length(); QPen myPen = pen(); myPen.setColor(myColor); qreal arrowSize = 10; painter->setPen(myPen); QBrush brush=painter->brush(); painter->setBrush(myColor); - - double angle = ::acos(line.dx() / line.length()); - angle=angle+90*2*Pi/360; + double angle =0; if(myClockWise) angle+=Pi; if (line.dy() >= 0) angle = (Pi) - angle; - QPointF arrowP1 = line.p1() + QPointF(sin(angle + Pi / 3) * arrowSize, + QPointF arrowP1 = p1 + QPointF(sin(angle + Pi / 3) * arrowSize, cos(angle + Pi / 3) * arrowSize); - QPointF arrowP2 = line.p1() + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, + QPointF arrowP2 = p1 + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, cos(angle + Pi - Pi / 3) * arrowSize); + QPointF arrowP21 = p2 + QPointF(sin(angle + Pi + Pi / 3) * arrowSize, + cos(angle + Pi + Pi / 3) * arrowSize); + QPointF arrowP22 = p2 + QPointF(sin(angle + Pi + Pi - Pi / 3) * arrowSize, + cos(angle + Pi + Pi - Pi / 3) * arrowSize); + arrowHead.clear(); - arrowHead << line.p1() << arrowP1 << arrowP2; + arrowHead << p1 << arrowP1 << arrowP2; + painter->drawPolygon(arrowHead); + arrowHead.clear(); + arrowHead << p2 << arrowP21 << arrowP22; painter->drawPolygon(arrowHead); painter->translate(-line.length(),-line.length()); painter->setBrush(brush); @@ -85,8 +104,8 @@ void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *op void WayPointCircle::refreshLocations() { - QLineF line(source->pos(),destination->pos()); - this->setRect(source->pos().x(),source->pos().y(),2*line.length(),2*line.length()); + QLineF line(my_center->pos(),my_radius->pos()); + this->setRect(my_center->pos().x(),my_center->pos().y(),2*line.length(),2*line.length()); } void WayPointCircle::waypointdeleted() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h index 4500a106d..0f4ce7ce2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h @@ -44,14 +44,15 @@ class WayPointCircle:public QObject,public QGraphicsEllipseItem Q_INTERFACES(QGraphicsItem) public: enum { Type = UserType + 9 }; - WayPointCircle(WayPointItem * from, WayPointItem * to,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); + WayPointCircle(WayPointItem * center, WayPointItem * radius,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); + WayPointCircle(HomeItem * center, WayPointItem * radius,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); int type() const; QPainterPath shape() const; void setColor(const QColor &color) { myColor = color; } private: - WayPointItem * source; - WayPointItem * destination; + QGraphicsItem * my_center; + QGraphicsItem * my_radius; MapGraphicItem * my_map; QPolygonF arrowHead; QColor myColor; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 318f1e05f..08c202e9f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -247,12 +247,14 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu } void WayPointItem::SetNumber(const int &value) { - emit WPNumberChanged(number,value,this); + int oldnumber=number; number=value; RefreshToolTip(); numberI->setText(QString::number(number)); numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); this->update(); + qDebug()<<"emit"<update(); } - void WayPointItem::WPDeleted(const int &onumber) + void WayPointItem::WPDeleted(const int &onumber,WayPointItem *waypoint) { - if(number>onumber) --number; - numberI->setText(QString::number(number)); - numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); - RefreshToolTip(); - this->update(); + Q_UNUSED(waypoint); + if(number>onumber) SetNumber(--number); } void WayPointItem::WPInserted(const int &onumber, WayPointItem *waypoint) { if(waypoint!=this) { - if(onumber<=number) ++number; - numberI->setText(QString::number(number)); - RefreshToolTip(); - this->update(); + if(onumber<=number) SetNumber(++number); } } @@ -324,25 +320,16 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { if(((oldnumber>number) && (newnumber<=number))) { - ++number; - numberI->setText(QString::number(number)); - numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); - RefreshToolTip(); + SetNumber(++number); } else if (((oldnumbernumber))) { - --number; - numberI->setText(QString::number(number)); - numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); - RefreshToolTip(); + SetNumber(--number); } else if (newnumber==number) { - ++number; - numberI->setText(QString::number(number)); - RefreshToolTip(); + SetNumber(++number); } - this->update(); } } int WayPointItem::type() const diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index dd25d51ed..3139980cf 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -196,7 +196,7 @@ public slots: * * @param number number of the WayPoint that was deleted */ - void WPDeleted(int const& number); + void WPDeleted(int const& number,WayPointItem *waypoint); /** * @brief Called when a WayPoint is renumbered * diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 4044e56a7..7ff8240a0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -26,7 +26,7 @@ */ #include "waypointline.h" #include - +#include "homeitem.h" const qreal Pi = 3.14; namespace mapcontrol @@ -35,10 +35,19 @@ WayPointLine::WayPointLine(WayPointItem *from, WayPointItem *to, MapGraphicItem destination(to),my_map(map),QGraphicsLineItem(map),myColor(color) { this->setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); - connect(source,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(destination,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(source,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); - connect(destination,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(from,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(to,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(from,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); +} + +WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map, QColor color):source(from), + destination(to),my_map(map),QGraphicsLineItem(map),myColor(color) +{ + this->setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); + connect(from,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); + connect(to,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); } int WayPointLine::type() const { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h index 420d64183..6d8985f77 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h @@ -44,13 +44,14 @@ class WayPointLine:public QObject,public QGraphicsLineItem public: enum { Type = UserType + 8 }; WayPointLine(WayPointItem * from, WayPointItem * to,MapGraphicItem * map,QColor color=Qt::green); + WayPointLine(HomeItem * from, WayPointItem * to,MapGraphicItem * map,QColor color=Qt::green); int type() const; QPainterPath shape() const; void setColor(const QColor &color) { myColor = color; } private: - WayPointItem * source; - WayPointItem * destination; + QGraphicsItem * source; + QGraphicsItem * destination; MapGraphicItem * my_map; QPolygonF arrowHead; QColor myColor; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 77d2aea86..1e9aac754 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -48,7 +48,7 @@ #include "positionactual.h" #include "homelocation.h" - +#include "pathplanmanager.h" #define allow_manual_home_location_move // ************************************************************************************* @@ -263,13 +263,18 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); - connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); + connect(m_map, SIGNAL(WPDeleted(int,WayPointItem*)), this, SLOT(WPDeleted(int,WayPointItem*))); connect(m_map,SIGNAL(OnWayPointDoubleClicked(WayPointItem*)),this,SLOT(wpDoubleClickEvent(WayPointItem*))); m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + + + pathPlanManager * plan=new pathPlanManager(new QWidget(),m_map); + plan->show(); + distBearing db; db.distance=100; db.bearing=0; @@ -285,6 +290,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) wp=new t_waypoint; wp->map_wp_item=p2; m_waypoint_list.append(wp); + // ************** // create various context menu (mouse right click menu) actions @@ -959,9 +965,10 @@ void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint) /** TODO: slot to do something upon Waypoint deletion */ -void OPMapGadgetWidget::WPDeleted(int const &number) +void OPMapGadgetWidget::WPDeleted(int const &number, WayPointItem *waypoint) { Q_UNUSED(number); + Q_UNUSED(waypoint); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index e787f1cf7..b6074bb8c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -176,7 +176,7 @@ private slots: void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); void WPValuesChanged(WayPointItem* waypoint); void WPInserted(int const& number, WayPointItem* waypoint); - void WPDeleted(int const& number); + void WPDeleted(int const& number, WayPointItem* waypoint); /** * @brief mouse right click context menu signals diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp index cc60dcc5b..8aa91e853 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp @@ -28,27 +28,37 @@ #include "ui_pathplanmanager.h" pathPlanManager::pathPlanManager(QWidget *parent,OPMapWidget *map): - QWidget(parent),myMap(map), + QDialog(parent, Qt::Dialog),myMap(map), ui(new Ui::pathPlanManager) { + waypoints=new QList(); ui->setupUi(this); - connect(myMap,SIGNAL(WPDeleted(int)),this,SLOT(on_WPDeleted(int))); + connect(myMap,SIGNAL(WPDeleted(int,WayPointItem*)),this,SLOT(on_WPDeleted(int,WayPointItem*))); connect(myMap,SIGNAL(WPInserted(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); - connect(myMap,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SLOT(on_WPNumberChanged(int,int,WayPointItem*))); - connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(on_WPValuesChanged(WayPointItem*))); - -} + connect(myMap,SIGNAL(WPCreated(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); + connect(myMap,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SLOT(refreshOverlays())); + connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(refreshOverlays())); + } pathPlanManager::~pathPlanManager() { delete ui; } -void pathPlanManager::on_WPDeleted(int wp_number) +void pathPlanManager::on_WPDeleted(int wp_numberint,WayPointItem * wp) { + waypoints->removeOne(wp); } void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) { + qDebug()<<"pathplanner waypoint added"; + waypoints->append(wp); + customData data; + data.mode=PathAction::MODE_FLYENDPOINT; + data.condition=PathAction::ENDCONDITION_NONE; + data.velocity=0; + wp->customData().setValue(data); + refreshOverlays(); } void pathPlanManager::on_WPNumberChanged(int oldNumber, int newNumber, WayPointItem * wp) @@ -58,3 +68,52 @@ void pathPlanManager::on_WPNumberChanged(int oldNumber, int newNumber, WayPointI void pathPlanManager::on_WPValuesChanged(WayPointItem * wp) { } +//typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, +//MODE_FLYCIRCLELEFT=3, MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, +//MODE_DRIVECIRCLERIGHT=7, MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; + +void pathPlanManager::refreshOverlays() +{ + myMap->deleteAllOverlays(); + qDebug()<<"foreach start"; + foreach(WayPointItem * wp,*waypoints) + { + qDebug()<<"wp:"<Number(); + customData data=wp->customData().value(); + switch(data.mode) + { + case PathAction::MODE_FLYENDPOINT: + case PathAction::MODE_FLYVECTOR: + case PathAction::MODE_DRIVEENDPOINT: + case PathAction::MODE_DRIVEVECTOR: + qDebug()<<"addline"; + if(wp->Number()==0) + myMap->WPLineCreate((HomeItem*)myMap->Home,wp); + else + myMap->WPLineCreate(findWayPointNumber(wp->Number()-1),wp); + break; + case PathAction::MODE_FLYCIRCLERIGHT: + case PathAction::MODE_DRIVECIRCLERIGHT: + myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,true); + break; + case PathAction::MODE_FLYCIRCLELEFT: + case PathAction::MODE_DRIVECIRCLELEFT: + myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,false); + break; + default: + break; + + } + } + qDebug()<<"foreach end"; +} + +WayPointItem * pathPlanManager::findWayPointNumber(int number) +{ + foreach(WayPointItem * wp,*waypoints) + { + if(wp->Number()==number) + return wp; + } + return NULL; +} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h index aa318f743..4f58b25e6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h @@ -30,14 +30,10 @@ #include #include "opmapcontrol/opmapcontrol.h" - -namespace Ui { -class pathPlanManager; -} -using namespace mapcontrol; -class pathPlanManager : public QWidget +#include "pathaction.h" +#include "waypoint.h" +namespace mapcontrol { - Q_OBJECT struct customData { float velocity; @@ -49,17 +45,30 @@ class pathPlanManager : public QWidget int jumpdestination; int errordestination; }; + +} +Q_DECLARE_METATYPE(mapcontrol::customData) +namespace Ui { +class pathPlanManager; +} +using namespace mapcontrol; +class pathPlanManager : public QDialog +{ + Q_OBJECT public: explicit pathPlanManager(QWidget *parent,OPMapWidget * map); ~pathPlanManager(); + WayPointItem *findWayPointNumber(int number); private slots: - void on_WPDeleted(int); + void refreshOverlays(); + void on_WPDeleted(int wp_numberint, WayPointItem *); void on_WPInserted(int,WayPointItem*); void on_WPNumberChanged(int,int,WayPointItem*); void on_WPValuesChanged(WayPointItem*); private: Ui::pathPlanManager *ui; OPMapWidget * myMap; + QList * waypoints; }; #endif // PATHPLANMANAGER_H From 08040ab5cf2235d53287bc3b7963fce467572e69 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 3 Jun 2012 19:19:00 +0100 Subject: [PATCH 015/116] GCS/MapLib - massive cleaning of the plugin --- .../opmapcontrol/src/mapwidget/homeitem.h | 2 +- .../src/mapwidget/mapgraphicitem.cpp | 1 + .../src/mapwidget/opmapwidget.cpp | 58 +- .../opmapcontrol/src/mapwidget/opmapwidget.h | 3 + .../src/mapwidget/waypointitem.cpp | 58 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 1 + .../src/plugins/opmap/opmapgadget.cpp | 35 +- .../src/plugins/opmap/opmapgadget.h | 7 +- .../opmap/opmapgadgetconfiguration.cpp | 19 +- .../plugins/opmap/opmapgadgetconfiguration.h | 5 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 587 ++++-------------- .../src/plugins/opmap/opmapgadgetwidget.h | 32 +- .../src/plugins/opmap/pathplanmanager.cpp | 27 +- .../src/plugins/opmap/pathplanmanager.h | 6 +- 14 files changed, 299 insertions(+), 542 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index eb16b6017..f8003335b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -53,7 +53,7 @@ namespace mapcontrol int SafeArea()const{return safearea;} void SetSafeArea(int const& value){safearea=value;} bool safe; - void SetCoord(internals::PointLatLng const& value){coord=value;} + void SetCoord(internals::PointLatLng const& value){emit homePositionChanged(value);coord=value;} internals::PointLatLng Coord()const{return coord;} void SetAltitude(int const& value){altitude=value;} int Altitude()const{return altitude;} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 2e098bc73..8620886ee 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -276,6 +276,7 @@ namespace mapcontrol { if(event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier)) this->setCursor(Qt::CrossCursor); + QGraphicsItem::keyPressEvent(event); } void MapGraphicItem::keyReleaseEvent(QKeyEvent *event) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 7dd2ef600..f09859395 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -220,6 +220,13 @@ namespace mapcontrol emit WPCreated(position,item); return item; } + WayPointItem* OPMapWidget::magicWPCreate() + { + WayPointItem* item=new WayPointItem(map,true); + item->SetShowNumber(false); + item->setParentItem(map); + return item; + } void OPMapWidget::WPCreate(WayPointItem* item) { ConnectWP(item); @@ -294,13 +301,46 @@ namespace mapcontrol emit WPDeleted(item->Number(),item); delete item; } - void OPMapWidget::WPDeleteAll() + void OPMapWidget::WPSetVisibleAll(bool value) { foreach(QGraphicsItem* i,map->childItems()) { WayPointItem* w=qgraphicsitem_cast(i); if(w) - delete w; + { + if(w->Number()!=-1) + w->setVisible(value); + } + } + } + void OPMapWidget::WPDeleteAll() + { + int x=0; + foreach(QGraphicsItem* i,map->childItems()) + { + WayPointItem* w=qgraphicsitem_cast(i); + if(w) + { + if(w->Number()!=-1) + { + emit WPDeleted(w->Number(),w); + delete w; + } + } + } + } + bool OPMapWidget::WPPresent() + { + foreach(QGraphicsItem* i,map->childItems()) + { + WayPointItem* w=qgraphicsitem_cast(i); + if(w) + { + if(w->Number()!=-1) + { + return true; + } + } } } void OPMapWidget::deleteAllOverlays() @@ -309,12 +349,12 @@ namespace mapcontrol { WayPointLine* w=qgraphicsitem_cast(i); if(w) - delete w; + w->deleteLater(); else { WayPointCircle* ww=qgraphicsitem_cast(i); if(ww) - delete ww; + ww->deleteLater(); } } } @@ -336,11 +376,11 @@ namespace mapcontrol void OPMapWidget::ConnectWP(WayPointItem *item) { - connect(item,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SIGNAL(WPNumberChanged(int,int,WayPointItem*))); - connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*))); - connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*))); - connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*))); - connect(this,SIGNAL(WPDeleted(int,WayPointItem*)),item,SLOT(WPDeleted(int,WayPointItem*))); + connect(item,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),Qt::DirectConnection); + connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*)),Qt::DirectConnection); + connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*)),Qt::DirectConnection); + connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*)),Qt::DirectConnection); + connect(this,SIGNAL(WPDeleted(int,WayPointItem*)),item,SLOT(WPDeleted(int,WayPointItem*)),Qt::DirectConnection); } void OPMapWidget::diagRefresh() { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 67d4e08fb..4da888bb1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -366,6 +366,9 @@ namespace mapcontrol WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise); WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise); void deleteAllOverlays(); + void WPSetVisibleAll(bool value); + WayPointItem *magicWPCreate(); + bool WPPresent(); private: internals::Core *core; MapGraphicItem *map; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 08c202e9f..9f6f87f6d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -53,10 +53,49 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(myHome) map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - qDebug()<<"RELATIVE DISTANCE SET ON CTOR1"<setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + myHome=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + myHome=h; + } + + if(myHome) + { + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + } + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); +} WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { text=0; @@ -81,7 +120,6 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(myHome) { map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - qDebug()<<"RELATIVE DISTANCE SET ON CTOR2"< list=map->childItems(); foreach(QGraphicsItem * obj,list) @@ -198,7 +235,6 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu if(myHome) { map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - qDebug()<<"RELATIVE DISTANCE SET ON MOUSEMOVEEVENT"<setText(coord_str+"\n"+relativeCoord_str); @@ -253,7 +289,6 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu numberI->setText(QString::number(number)); numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); this->update(); - qDebug()<<"emit"<onumber) SetNumber(--number); + int n=number; + if(number>onumber) SetNumber(--n); } void WayPointItem::WPInserted(const int &onumber, WayPointItem *waypoint) { + if(Number()==-1) + return; + if(waypoint!=this) { if(onumber<=number) SetNumber(++number); @@ -358,7 +397,10 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7\n%8").arg(QString::number(WayPointItem::number)).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + if(Number()!=-1) + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7\n%8").arg(QString::number(Number())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + else + setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); } int WayPointItem::snumber=0; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 3139980cf..e0bd594b5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -64,6 +64,7 @@ public: * @return */ WayPointItem(internals::PointLatLng const& coord,int const& altitude,MapGraphicItem* map,wptype type=absolute); + WayPointItem(MapGraphicItem* map,bool magicwaypoint); /** * @brief Constructer * diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp index be2a4e476..388fd57bb 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp @@ -26,31 +26,42 @@ */ #include "opmapgadget.h" #include "opmapgadgetwidget.h" -#include "opmapgadgetconfiguration.h" OPMapGadget::OPMapGadget(QString classId, OPMapGadgetWidget *widget, QWidget *parent) : IUAVGadget(classId, parent), - m_widget(widget) + m_widget(widget),m_config(NULL) { + connect(m_widget,SIGNAL(defaultLocationAndZoomChanged(double,double,double)),this,SLOT(saveConfiguration(double,double,double))); } OPMapGadget::~OPMapGadget() { delete m_widget; } +void OPMapGadget::saveConfiguration(double lng,double lat,double zoom) +{ + if(m_config) + { + m_config->setLatitude(lat); + m_config->setLongitude(lng); + m_config->setZoom(zoom); + m_config->saveConfig(); + } +} void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) { - OPMapGadgetConfiguration *m = qobject_cast(config); + m_config = qobject_cast(config); - m_widget->setMapProvider(m->mapProvider()); - m_widget->setZoom(m->zoom()); - m_widget->setPosition(QPointF(m->longitude(), m->latitude())); - m_widget->setUseOpenGL(m->useOpenGL()); - m_widget->setShowTileGridLines(m->showTileGridLines()); - m_widget->setAccessMode(m->accessMode()); - m_widget->setUseMemoryCache(m->useMemoryCache()); - m_widget->setCacheLocation(m->cacheLocation()); - m_widget->SetUavPic(m->uavSymbol()); + m_widget->setMapProvider(m_config->mapProvider()); + m_widget->setZoom(m_config->zoom()); + m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); + m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); + m_widget->setUseOpenGL(m_config->useOpenGL()); + m_widget->setShowTileGridLines(m_config->showTileGridLines()); + m_widget->setAccessMode(m_config->accessMode()); + m_widget->setUseMemoryCache(m_config->useMemoryCache()); + m_widget->setCacheLocation(m_config->cacheLocation()); + m_widget->SetUavPic(m_config->uavSymbol()); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h index 030caf986..87866c43f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h @@ -30,6 +30,7 @@ #include #include "opmapgadgetwidget.h" +#include "opmapgadgetconfiguration.h" class IUAVGadget; //class QList; @@ -47,10 +48,12 @@ public: ~OPMapGadget(); QWidget *widget() { return m_widget; } - void loadConfiguration(IUAVGadgetConfiguration* config); - + void loadConfiguration(IUAVGadgetConfiguration* m_config); private: OPMapGadgetWidget *m_widget; + OPMapGadgetConfiguration *m_config; +private slots: + void saveConfiguration(double lng, double lat, double zoom); }; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp index 67d1d1f98..7e77b0031 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp @@ -41,7 +41,8 @@ OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* m_useMemoryCache(true), m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()), m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")), - m_maxUpdateRate(2000) // ms + m_maxUpdateRate(2000), // ms + m_settings(qSettings) { //if a saved configuration exists load it @@ -97,7 +98,21 @@ IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone() return m; } - +void OPMapGadgetConfiguration::saveConfig() const { + if(!m_settings) + return; + m_settings->setValue("mapProvider", m_mapProvider); + m_settings->setValue("defaultZoom", m_defaultZoom); + m_settings->setValue("defaultLatitude", m_defaultLatitude); + m_settings->setValue("defaultLongitude", m_defaultLongitude); + m_settings->setValue("useOpenGL", m_useOpenGL); + m_settings->setValue("showTileGridLines", m_showTileGridLines); + m_settings->setValue("accessMode", m_accessMode); + m_settings->setValue("useMemoryCache", m_useMemoryCache); + m_settings->setValue("uavSymbol", m_uavSymbol); + m_settings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); + m_settings->setValue("maxUpdateRate", m_maxUpdateRate); +} void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("mapProvider", m_mapProvider); qSettings->setValue("defaultZoom", m_defaultZoom); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h index 1e630dc00..ffd0c5a08 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h @@ -65,8 +65,8 @@ public: bool useMemoryCache() const { return m_useMemoryCache; } QString cacheLocation() const { return m_cacheLocation; } QString uavSymbol() const { return m_uavSymbol; } - int maxUpdateRate() const { return m_maxUpdateRate; } - + int maxUpdateRate() const { return m_maxUpdateRate; } + void saveConfig() const; public slots: void setMapProvider(QString provider) { m_mapProvider = provider; } void setZoom(int zoom) { m_defaultZoom = zoom; } @@ -92,6 +92,7 @@ private: QString m_cacheLocation; QString m_uavSymbol; int m_maxUpdateRate; + QSettings * m_settings; }; #endif // OPMAP_GADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 1e9aac754..3dabcd91e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -131,17 +131,6 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_home_position.altitude = altitude; m_home_position.locked = false; - // ************** - // default magic waypoint params - - m_magic_waypoint.map_wp_item = NULL; - m_magic_waypoint.coord = m_home_position.coord; - m_magic_waypoint.altitude = altitude; - m_magic_waypoint.description = "Magic waypoint"; - m_magic_waypoint.locked = false; - m_magic_waypoint.time_seconds = 0; - m_magic_waypoint.hold_time_seconds = 0; - // ************** // create the widget that holds the user controls and the map @@ -194,50 +183,17 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) layout->addWidget(m_map); m_widget->mapWidget->setLayout(layout); - // ************** - // set the user control options - - // TODO: this switch does not make sense, does it?? - - switch (m_map_mode) - { - case Normal_MapMode: m_widget->toolButtonMagicWaypointMapMode->setChecked(false); m_widget->toolButtonNormalMapMode->setChecked(true); hideMagicWaypointControls(); - break; - - case MagicWaypoint_MapMode: - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - showMagicWaypointControls(); - break; - - default: - m_map_mode = Normal_MapMode; - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); - break; - } m_widget->labelUAVPos->setText("---"); m_widget->labelMapPos->setText("---"); m_widget->labelMousePos->setText("---"); m_widget->labelMapZoom->setText("---"); - - // Splitter is not used at the moment: - // m_widget->splitter->setCollapsible(1, false); - - // set the size of the collapsable widgets - //QList m_SizeList; - //m_SizeList << 0 << 0 << 0; - //m_widget->splitter->setSizes(m_SizeList); - m_widget->progressBarMap->setMaximum(1); - #if defined(Q_OS_MAC) #elif defined(Q_OS_WIN) m_widget->comboBoxFindPlace->clear(); @@ -246,11 +202,6 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) #else #endif - - - // ************** - // map stuff - connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals @@ -260,10 +211,9 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals - connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); - connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); - connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); - connect(m_map, SIGNAL(WPDeleted(int,WayPointItem*)), this, SLOT(WPDeleted(int,WayPointItem*))); + // connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); + // connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); + // connect(m_map, SIGNAL(WPDeleted(int,WayPointItem*)), this, SLOT(WPDeleted(int,WayPointItem*))); connect(m_map,SIGNAL(OnWayPointDoubleClicked(WayPointItem*)),this,SLOT(wpDoubleClickEvent(WayPointItem*))); m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position @@ -274,7 +224,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) pathPlanManager * plan=new pathPlanManager(new QWidget(),m_map); plan->show(); - +/* distBearing db; db.distance=100; db.bearing=0; @@ -290,6 +240,9 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) wp=new t_waypoint; wp->map_wp_item=p2; m_waypoint_list.append(wp); +*/ + magicWayPoint=m_map->magicWPCreate(); + magicWayPoint->setVisible(false); // ************** // create various context menu (mouse right click menu) actions @@ -330,10 +283,8 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_statusUpdateTimer = new QTimer(); m_statusUpdateTimer->setInterval(200); -// m_statusUpdateTimer->setInterval(m_maxUpdateRate); connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); m_statusUpdateTimer->start(); - // ************** m_map->setFocus(); @@ -349,29 +300,6 @@ OPMapGadgetWidget::~OPMapGadgetWidget() m_map->SetShowUAV(false); // " " } - - // this destructor doesn't appear to be called at shutdown??? - -// #if defined(Q_OS_MAC) -// #elif defined(Q_OS_WIN) -// saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); -// #else -// #endif - - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - - - // todo: - - - delete wp->map_wp_item; - } - m_waypoint_list_mutex.unlock(); - m_waypoint_list.clear(); - if (m_map) { delete m_map; @@ -384,24 +312,18 @@ OPMapGadgetWidget::~OPMapGadgetWidget() void OPMapGadgetWidget::resizeEvent(QResizeEvent *event) { - qDebug("opmap: resizeEvent"); - QWidget::resizeEvent(event); } void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) { - qDebug("opmap: mouseMoveEvent"); - if (m_widget && m_map) { } if (event->buttons() & Qt::LeftButton) { -// QPoint pos = event->pos(); } - QWidget::mouseMoveEvent(event); } void OPMapGadgetWidget::wpDoubleClickEvent(WayPointItem *wp) @@ -424,7 +346,6 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) // current mouse position QPoint p = m_map->mapFromGlobal(event->globalPos()); m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); -// m_context_menu_lat_lon = m_map->currentMousePosition(); if (!m_map->contentsRect().contains(p)) return; // the mouse click was not on the map @@ -445,26 +366,19 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) // **************** // Dynamically create the popup menu - QMenu menu(this); - - menu.addAction(closeAct1); - - menu.addSeparator(); - - menu.addAction(reloadAct); - - menu.addSeparator(); - - menu.addAction(ripAct); - - menu.addSeparator(); + contextMenu.addAction(closeAct1); + contextMenu.addSeparator(); + contextMenu.addAction(reloadAct); + contextMenu.addSeparator(); + contextMenu.addAction(ripAct); + contextMenu.addSeparator(); QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); for (int i = 0; i < maxUpdateRateAct.count(); i++) maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); - menu.addMenu(&maxUpdateRateSubMenu); + contextMenu.addMenu(&maxUpdateRateSubMenu); - menu.addSeparator(); + contextMenu.addSeparator(); switch (m_map_mode) { @@ -482,19 +396,19 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) QMenu mapModeSubMenu(tr("Map mode") + s, this); for (int i = 0; i < mapModeAct.count(); i++) mapModeSubMenu.addAction(mapModeAct.at(i)); - menu.addMenu(&mapModeSubMenu); + contextMenu.addMenu(&mapModeSubMenu); - menu.addSeparator(); + contextMenu.addSeparator(); QMenu copySubMenu(tr("Copy"), this); copySubMenu.addAction(copyMouseLatLonToClipAct); copySubMenu.addAction(copyMouseLatToClipAct); copySubMenu.addAction(copyMouseLonToClipAct); - menu.addMenu(©SubMenu); + contextMenu.addMenu(©SubMenu); - menu.addSeparator(); - - menu.addSeparator(); + contextMenu.addSeparator(); + contextMenu.addAction(changeDefaultLocalAndZoom); + contextMenu.addSeparator(); QMenu safeArea("Safety Area definitions"); // menu.addAction(showSafeAreaAct); @@ -503,68 +417,68 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) safeAreaSubMenu.addAction(safeAreaAct.at(i)); safeArea.addMenu(&safeAreaSubMenu); safeArea.addAction(showSafeAreaAct); - menu.addMenu(&safeArea); + contextMenu.addMenu(&safeArea); - menu.addSeparator(); + contextMenu.addSeparator(); - menu.addAction(showCompassAct); + contextMenu.addAction(showCompassAct); - menu.addAction(showDiagnostics); + contextMenu.addAction(showDiagnostics); - menu.addSeparator()->setText(tr("Zoom")); + contextMenu.addSeparator()->setText(tr("Zoom")); - menu.addAction(zoomInAct); - menu.addAction(zoomOutAct); + contextMenu.addAction(zoomInAct); + contextMenu.addAction(zoomOutAct); QMenu zoomSubMenu(tr("&Zoom ") + "(" + QString::number(m_map->ZoomTotal()) + ")", this); for (int i = 0; i < zoomAct.count(); i++) zoomSubMenu.addAction(zoomAct.at(i)); - menu.addMenu(&zoomSubMenu); + contextMenu.addMenu(&zoomSubMenu); - menu.addSeparator(); + contextMenu.addSeparator(); - menu.addAction(goMouseClickAct); + contextMenu.addAction(goMouseClickAct); - menu.addSeparator()->setText(tr("HOME")); + contextMenu.addSeparator()->setText(tr("HOME")); - menu.addAction(setHomeAct); - menu.addAction(showHomeAct); - menu.addAction(goHomeAct); + contextMenu.addAction(setHomeAct); + contextMenu.addAction(showHomeAct); + contextMenu.addAction(goHomeAct); // **** // uav trails - - menu.addSeparator()->setText(tr("UAV Trail")); - + QMenu uav_menu(tr("UAV")); + uav_menu.addSeparator()->setText(tr("UAV Trail")); + contextMenu.addMenu(&uav_menu); QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this); for (int i = 0; i < uavTrailTypeAct.count(); i++) uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i)); - menu.addMenu(&uavTrailTypeSubMenu); + uav_menu.addMenu(&uavTrailTypeSubMenu); QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this); for (int i = 0; i < uavTrailTimeAct.count(); i++) uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i)); - menu.addMenu(&uavTrailTimeSubMenu); + uav_menu.addMenu(&uavTrailTimeSubMenu); QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this); for (int i = 0; i < uavTrailDistanceAct.count(); i++) uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i)); - menu.addMenu(&uavTrailDistanceSubMenu); + uav_menu.addMenu(&uavTrailDistanceSubMenu); - menu.addAction(showTrailAct); + uav_menu.addAction(showTrailAct); - menu.addAction(showTrailLineAct); + uav_menu.addAction(showTrailLineAct); - menu.addAction(clearUAVtrailAct); + uav_menu.addAction(clearUAVtrailAct); // **** - menu.addSeparator()->setText(tr("UAV")); + uav_menu.addSeparator()->setText(tr("UAV")); - menu.addAction(showUAVAct); - menu.addAction(followUAVpositionAct); - menu.addAction(followUAVheadingAct); - menu.addAction(goUAVAct); + uav_menu.addAction(showUAVAct); + uav_menu.addAction(followUAVpositionAct); + uav_menu.addAction(followUAVheadingAct); + uav_menu.addAction(goUAVAct); // ********* @@ -573,93 +487,51 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) case Normal_MapMode: // only show the waypoint stuff if not in 'magic waypoint' mode - menu.addSeparator()->setText(tr("Waypoints")); + contextMenu.addSeparator()->setText(tr("Waypoints")); - menu.addAction(wayPointEditorAct); - menu.addAction(addWayPointAct); + contextMenu.addAction(wayPointEditorAct); + contextMenu.addAction(addWayPointAct); if (m_mouse_waypoint) { // we have a waypoint under the mouse - menu.addAction(editWayPointAct); + contextMenu.addAction(editWayPointAct); lockWayPointAct->setChecked(waypoint_locked); - menu.addAction(lockWayPointAct); + contextMenu.addAction(lockWayPointAct); if (!waypoint_locked) - menu.addAction(deleteWayPointAct); + contextMenu.addAction(deleteWayPointAct); } - m_waypoint_list_mutex.lock(); - if (m_waypoint_list.count() > 0) - menu.addAction(clearWayPointsAct); // we have waypoints - m_waypoint_list_mutex.unlock(); - + if (m_map->WPPresent()) + contextMenu.addAction(clearWayPointsAct); // we have waypoints break; case MagicWaypoint_MapMode: - menu.addSeparator()->setText(tr("Waypoints")); - menu.addAction(homeMagicWaypointAct); + contextMenu.addSeparator()->setText(tr("Waypoints")); + contextMenu.addAction(homeMagicWaypointAct); break; } // ********* - menu.addSeparator(); + contextMenu.addSeparator(); - menu.addAction(closeAct2); + contextMenu.addAction(closeAct2); - menu.exec(event->globalPos()); // popup the menu + contextMenu.exec(event->globalPos()); // popup the menu // **************** } -void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event) -{ - qDebug() << "opmap: keyPressEvent, key =" << event->key() << endl; - - switch (event->key()) - { - case Qt::Key_Escape: - break; - - case Qt::Key_F1: - break; - - case Qt::Key_F2: - break; - - case Qt::Key_Up: - break; - - case Qt::Key_Down: - break; - - case Qt::Key_Left: - break; - - case Qt::Key_Right: - break; - - case Qt::Key_PageUp: - break; - - case Qt::Key_PageDown: - break; - } -} - // ************************************************************************************* // timer signals /** Updates the UAV position on the map. It is called every 200ms by a timer. - - TODO: consider updating upon object update, not timer. - - from Pip: No don't update on object update - had reports that peoples PC's can't cope with high update rates - have had to allow user to set map update from 100ms to 5 seconds (depending on their PC's graphics processing ability), so this needs to be kept on a timer. - */ +*/ void OPMapGadgetWidget::updatePosition() { double uav_latitude, uav_longitude, uav_altitude, uav_yaw; @@ -740,7 +612,7 @@ void OPMapGadgetWidget::updateMousePos() QPoint p = m_map->mapFromGlobal(QCursor::pos()); internals::PointLatLng lat_lon = m_map->GetFromLocalToLatLng(p); // fetch the current lat/lon mouse position - + lastLatLngMouse=lat_lon; if (!m_map->contentsRect().contains(p)) return; // the mouse is not on the map @@ -795,11 +667,6 @@ void OPMapGadgetWidget::updateMousePos() if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position { internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); - -// double dist = distance(home_lat_lon, uav_pos); -// double bear = bearing(home_lat_lon, uav_pos); -// s += " " + QString::number(dist * 1000, 'f', 1) + "m"; -// s += " " + QString::number(bear, 'f', 1) + "deg"; } } m_widget->labelMousePos->setText(s); @@ -855,16 +722,11 @@ void OPMapGadgetWidget::OnTilesStillToLoad(int number) if (!m_widget || !m_map) return; -// if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) -// m_widget->progressBarMap->setMaximum(number); - if (m_widget->progressBarMap->maximum() < number) m_widget->progressBarMap->setMaximum(number); m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar -// m_widget->labelNumTilesToLoad->setText(QString::number(number)); - m_prev_tile_number = number; } @@ -875,7 +737,6 @@ void OPMapGadgetWidget::OnTileLoadStart() { if (!m_widget || !m_map) return; - m_widget->progressBarMap->setVisible(true); } @@ -915,44 +776,6 @@ void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumb Q_UNUSED(waypoint); } -void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) -{ -// qDebug("opmap: WPValuesChanged"); - - switch (m_map_mode) - { - case Normal_MapMode: - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { // search for the waypoint in our own waypoint list and update it - if (!wp) continue; - if (!wp->map_wp_item) continue; - if (wp->map_wp_item != waypoint) continue; - // found the waypoint in our list - wp->coord = waypoint->Coord(); - wp->altitude = waypoint->Altitude(); - wp->description = waypoint->Description(); - break; - } - m_waypoint_list_mutex.unlock(); - break; - - case MagicWaypoint_MapMode: - // update our copy of the magic waypoint - if (m_magic_waypoint.map_wp_item && m_magic_waypoint.map_wp_item == waypoint) - { - m_magic_waypoint.coord = waypoint->Coord(); - m_magic_waypoint.altitude = waypoint->Altitude(); - m_magic_waypoint.description = waypoint->Description(); - - // move the UAV to the magic waypoint position - // moveToMagicWaypointPosition(); - } - break; - } - -} - /** TODO: slot to do something upon Waypoint insertion */ @@ -1227,6 +1050,27 @@ void OPMapGadgetWidget::setZoom(int zoom) m_map->SetMouseWheelZoomType(zoom_type); } +void OPMapGadgetWidget::setHomePosition(QPointF pos) +{ + if (!m_widget || !m_map) + return; + + double latitude = pos.y(); + double longitude = pos.x(); + + if (latitude != latitude || longitude != longitude) + return; // nan prevention + + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; + + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; + + m_map->Home->SetCoord(internals::PointLatLng(latitude, longitude)); +} void OPMapGadgetWidget::setPosition(QPointF pos) { @@ -1299,21 +1143,12 @@ void OPMapGadgetWidget::setCacheLocation(QString cacheLocation) if (cacheLocation.isEmpty()) return; -// #if defined(Q_WS_WIN) -// if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; -// #elif defined(Q_WS_X11) - if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #elif defined(Q_WS_MAC) -// if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #endif + if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); QDir dir; if (!dir.exists(cacheLocation)) if (!dir.mkpath(cacheLocation)) return; - -// qDebug() << "opmap: map cache dir: " << cacheLocation; - m_map->configuration->SetCacheLocation(cacheLocation); } @@ -1351,32 +1186,8 @@ void OPMapGadgetWidget::setMapMode(opMapModeType mode) hideMagicWaypointControls(); - // delete the magic waypoint from the map - if (m_magic_waypoint.map_wp_item) - { - m_magic_waypoint.coord = m_magic_waypoint.map_wp_item->Coord(); - m_magic_waypoint.altitude = m_magic_waypoint.map_wp_item->Altitude(); - m_magic_waypoint.description = m_magic_waypoint.map_wp_item->Description(); - m_magic_waypoint.map_wp_item = NULL; - } - m_map->WPDeleteAll(); - - // restore the normal waypoints on the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - if (!wp->map_wp_item) continue; - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - m_waypoint_list_mutex.unlock(); + magicWayPoint->setVisible(false); + m_map->WPSetVisibleAll(true); break; @@ -1389,25 +1200,9 @@ void OPMapGadgetWidget::setMapMode(opMapModeType mode) showMagicWaypointControls(); // delete the normal waypoints from the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - if (!wp->map_wp_item) continue; - wp->coord = wp->map_wp_item->Coord(); - wp->altitude = wp->map_wp_item->Altitude(); - wp->description = wp->map_wp_item->Description(); - wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0; - wp->map_wp_item = NULL; - } - m_map->WPDeleteAll(); - m_waypoint_list_mutex.unlock(); - // restore the magic waypoint on the map - m_magic_waypoint.map_wp_item = m_map->WPCreate(m_magic_waypoint.coord, m_magic_waypoint.altitude, m_magic_waypoint.description); - m_magic_waypoint.map_wp_item->setZValue(10 + m_magic_waypoint.map_wp_item->Number()); - m_magic_waypoint.map_wp_item->SetShowNumber(false); - m_magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + m_map->WPSetVisibleAll(false); + magicWayPoint->setVisible(true); break; } @@ -1436,7 +1231,7 @@ void OPMapGadgetWidget::createActions() reloadAct->setShortcut(tr("F5")); reloadAct->setStatusTip(tr("Reload the map tiles")); connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); - + this->addAction(reloadAct); ripAct = new QAction(tr("&Rip map"), this); ripAct->setStatusTip(tr("Rip the map tiles")); connect(ripAct, SIGNAL(triggered()), this, SLOT(onRipAct_triggered())); @@ -1477,15 +1272,21 @@ void OPMapGadgetWidget::createActions() showUAVAct->setChecked(true); connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); + changeDefaultLocalAndZoom = new QAction(tr("Set default zoom and location"), this); + changeDefaultLocalAndZoom->setStatusTip(tr("Changes the map default zoom and location to the current values")); + connect(changeDefaultLocalAndZoom, SIGNAL(triggered()), this, SLOT(onChangeDefaultLocalAndZoom())); + zoomInAct = new QAction(tr("Zoom &In"), this); zoomInAct->setShortcut(Qt::Key_PageUp); zoomInAct->setStatusTip(tr("Zoom the map in")); connect(zoomInAct, SIGNAL(triggered()), this, SLOT(onGoZoomInAct_triggered())); + this->addAction(zoomInAct); zoomOutAct = new QAction(tr("Zoom &Out"), this); zoomOutAct->setShortcut(Qt::Key_PageDown); zoomOutAct->setStatusTip(tr("Zoom the map out")); connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(onGoZoomOutAct_triggered())); + this->addAction(zoomOutAct); goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this); goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse")); @@ -1537,6 +1338,7 @@ void OPMapGadgetWidget::createActions() addWayPointAct->setShortcut(tr("Ctrl+A")); addWayPointAct->setStatusTip(tr("Add waypoint")); connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); + this->addAction(addWayPointAct); editWayPointAct = new QAction(tr("&Edit waypoint"), this); editWayPointAct->setShortcut(tr("Ctrl+E")); @@ -1814,7 +1616,12 @@ void OPMapGadgetWidget::onMaxUpdateRateActGroup_triggered(QAction *action) if (!m_widget || !m_map || !action) return; - setMaxUpdateRate(action->data().toInt()); + setMaxUpdateRate(action->data().toInt()); +} + +void OPMapGadgetWidget::onChangeDefaultLocalAndZoom() +{ + emit defaultLocationAndZoomChanged(m_map->CurrentPosition().Lng(),m_map->CurrentPosition().Lat(),m_map->ZoomTotal()); } void OPMapGadgetWidget::onGoMouseClickAct_triggered() @@ -1940,36 +1747,20 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() if (m_map_mode != Normal_MapMode) return; - m_waypoint_list_mutex.lock(); + // m_waypoint_list_mutex.lock(); // create a waypoint on the map at the last known mouse position - t_waypoint *wp = new t_waypoint; - wp->map_wp_item = NULL; - wp->coord = m_context_menu_lat_lon; - wp->altitude = 0; - wp->description = ""; - wp->locked = false; - wp->time_seconds = 0; - wp->hold_time_seconds = 0; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); + internals::PointLatLng coord; + if(this->contextMenu.isVisible()) + coord = m_context_menu_lat_lon; + else + coord=lastLatLngMouse; + m_map->WPCreate(coord, 0, ""); - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); + //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - if (wp->map_wp_item) - { - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - - // and remember it in our own local waypoint list - m_waypoint_list.append(wp); - - m_waypoint_list_mutex.unlock(); } @@ -2021,11 +1812,6 @@ void OPMapGadgetWidget::onLockWayPointAct_triggered() m_mouse_waypoint = NULL; } - -/** - * TODO: unused for v1.0 - */ - void OPMapGadgetWidget::onDeleteWayPointAct_triggered() { if (!m_widget || !m_map) @@ -2037,51 +1823,10 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() if (!m_mouse_waypoint) return; - bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; - - if (locked) return; // waypoint is locked - - QMutexLocker locker(&m_waypoint_list_mutex); - - for (int i = 0; i < m_waypoint_list.count(); i++) - { - t_waypoint *wp = m_waypoint_list.at(i); - if (!wp) continue; - if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; - // delete the waypoint from the map - m_map->WPDelete(wp->map_wp_item); - - // delete the waypoint from our local waypoint list - m_waypoint_list.removeAt(i); - - delete wp; - - break; - } -// -// foreach (t_waypoint *wp, m_waypoint_list) -// { -// if (!wp) continue; -// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; -// -// // delete the waypoint from the map -// m_map->WPDelete(wp->map_wp_item); -// -// // delete the waypoint from our local waypoint list -// m_waypoint_list.removeOne(wp); -// -// delete wp; -// -// break; -// } - - m_mouse_waypoint = NULL; + m_map->WPDelete(m_mouse_waypoint); } -/** - * TODO: No Waypoint support in v1.0 - */ void OPMapGadgetWidget::onClearWayPointsAct_triggered() { if (!m_widget || !m_map) @@ -2090,21 +1835,9 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() if (m_map_mode != Normal_MapMode) return; - QMutexLocker locker(&m_waypoint_list_mutex); - m_map->WPDeleteAll(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (wp) - { - delete wp; - wp = NULL; - } - } - - m_waypoint_list.clear(); -} + } void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() @@ -2147,10 +1880,7 @@ void OPMapGadgetWidget::homeMagicWaypoint() if (m_map_mode != MagicWaypoint_MapMode) return; - m_magic_waypoint.coord = m_home_position.coord; - - if (m_magic_waypoint.map_wp_item) - m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); + magicWayPoint->SetCoord(m_home_position.coord); } // ************************************************************************************* @@ -2163,60 +1893,6 @@ void OPMapGadgetWidget::moveToMagicWaypointPosition() if (m_map_mode != MagicWaypoint_MapMode) return; - -// internals::PointLatLng coord = magic_waypoint.coord; -// double altitude = magic_waypoint.altitude; - - - // ToDo: - -} - -// ************************************************************************************* -// temporary until an object is created for managing the save/restore - -// load the contents of a simple text file into a combobox -void OPMapGadgetWidget::loadComboBoxLines(QComboBox *comboBox, QString filename) -{ - if (!comboBox) return; - if (filename.isNull() || filename.isEmpty()) return; - - QFile file(filename); - if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) - return; - - QTextStream in(&file); - - while (!in.atEnd()) - { - QString line = in.readLine().simplified(); - if (line.isNull() || line.isEmpty()) continue; - comboBox->addItem(line); - } - - file.close(); -} - -// save a combobox text contents to a simple text file -void OPMapGadgetWidget::saveComboBoxLines(QComboBox *comboBox, QString filename) -{ - if (!comboBox) return; - if (filename.isNull() || filename.isEmpty()) return; - - QFile file(filename); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) - return; - - QTextStream out(&file); - - for (int i = 0; i < comboBox->count(); i++) - { - QString line = comboBox->itemText(i).simplified(); - if (line.isNull() || line.isEmpty()) continue; - out << line << "\n"; - } - - file.close(); } // ************************************************************************************* @@ -2248,25 +1924,20 @@ void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() { // calcute the bearing and distance from the home position to the magic waypoint - double dist = distance(m_home_position.coord, m_magic_waypoint.coord); - double bear = bearing(m_home_position.coord, m_magic_waypoint.coord); + double dist = distance(m_home_position.coord, magicWayPoint->Coord()); + double bear = bearing(m_home_position.coord, magicWayPoint->Coord()); // get the maximum safe distance - in kilometers double boundry_dist = (double)m_map->Home->SafeArea() / 1000; -// if (dist <= boundry_dist) -// return; // the magic waypoint is still within the safe area, don't move it - if (dist > boundry_dist) dist = boundry_dist; - // move the magic waypoint - - m_magic_waypoint.coord = destPoint(m_home_position.coord, bear, dist); + // move the magic waypoint; if (m_map_mode == MagicWaypoint_MapMode) { // move the on-screen waypoint - if (m_magic_waypoint.map_wp_item) - m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); + if (magicWayPoint) + magicWayPoint->SetCoord(destPoint(m_home_position.coord, bear, dist)); } } @@ -2281,22 +1952,6 @@ double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::Point double lat2 = to.Lat() * deg_to_rad; double lon2 = to.Lng() * deg_to_rad; - // *********************** - // Haversine formula -/* - double delta_lat = lat2 - lat1; - double delta_lon = lon2 - lon1; - - double t1 = sin(delta_lat / 2); - double t2 = sin(delta_lon / 2); - double a = (t1 * t1) + cos(lat1) * cos(lat2) * (t2 * t2); - double c = 2 * atan2(sqrt(a), sqrt(1 - a)); - - return (earth_mean_radius * c); -*/ - // *********************** - // Spherical Law of Cosines - return (acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1)) * earth_mean_radius); // *********************** diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index b6074bb8c..50441b837 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -74,18 +74,6 @@ typedef struct t_home bool locked; } t_home; -// local waypoint list item structure -typedef struct t_waypoint -{ - mapcontrol::WayPointItem *map_wp_item; - internals::PointLatLng coord; - double altitude; - QString description; - bool locked; - int time_seconds; - int hold_time_seconds; -} t_waypoint; - // ****************************************************** enum opMapModeType { Normal_MapMode = 0, @@ -120,7 +108,9 @@ public: void setMapMode(opMapModeType mode); void SetUavPic(QString UAVPic); void setMaxUpdateRate(int update_rate); - + void setHomePosition(QPointF pos); +signals: + void defaultLocationAndZoomChanged(double lng,double lat,double zoom); public slots: void homePositionUpdated(UAVObject *); @@ -131,7 +121,6 @@ protected: void resizeEvent(QResizeEvent *event); void mouseMoveEvent(QMouseEvent *event); void contextMenuEvent(QContextMenuEvent *event); - void keyPressEvent(QKeyEvent* event); private slots: void wpDoubleClickEvent(WayPointItem *wp); void updatePosition(); @@ -174,7 +163,6 @@ private slots: * Unused for now, hooks for future waypoint support */ void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); - void WPValuesChanged(WayPointItem* waypoint); void WPInserted(int const& number, WayPointItem* waypoint); void WPDeleted(int const& number, WayPointItem* waypoint); @@ -218,7 +206,7 @@ private slots: void onUAVTrailTimeActGroup_triggered(QAction *action); void onUAVTrailDistanceActGroup_triggered(QAction *action); void onMaxUpdateRateActGroup_triggered(QAction *action); - + void onChangeDefaultLocalAndZoom(); void on_tbFind_clicked(); private: @@ -241,8 +229,6 @@ private: t_home m_home_position; - t_waypoint m_magic_waypoint; - QStringList findPlaceWordList; QCompleter *findPlaceCompleter; @@ -265,9 +251,6 @@ private: mapcontrol::WayPointItem *m_mouse_waypoint; - QList m_waypoint_list; - QMutex m_waypoint_list_mutex; - QMutex m_map_mutex; bool m_telemetry_connected; @@ -306,6 +289,7 @@ private: QAction *homeMagicWaypointAct; QAction *showSafeAreaAct; + QAction *changeDefaultLocalAndZoom; QActionGroup *safeAreaActGroup; QList safeAreaAct; @@ -334,9 +318,6 @@ private: void moveToMagicWaypointPosition(); - void loadComboBoxLines(QComboBox *comboBox, QString filename); - void saveComboBoxLines(QComboBox *comboBox, QString filename); - void hideMagicWaypointControls(); void showMagicWaypointControls(); @@ -353,6 +334,9 @@ private: void setMapFollowingMode(); bool setHomeLocationObject(); + QMenu contextMenu; + internals::PointLatLng lastLatLngMouse; + WayPointItem * magicWayPoint; }; #endif /* OPMAP_GADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp index 8aa91e853..c4ac4f8e1 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp @@ -31,9 +31,9 @@ pathPlanManager::pathPlanManager(QWidget *parent,OPMapWidget *map): QDialog(parent, Qt::Dialog),myMap(map), ui(new Ui::pathPlanManager) { - waypoints=new QList(); + waypoints=new QList >(); ui->setupUi(this); - connect(myMap,SIGNAL(WPDeleted(int,WayPointItem*)),this,SLOT(on_WPDeleted(int,WayPointItem*))); + connect(myMap,SIGNAL(WPDeleted(int,WayPointItem*)),this,SLOT(on_WPDeleted(int,WayPointItem*)),Qt::DirectConnection); connect(myMap,SIGNAL(WPInserted(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); connect(myMap,SIGNAL(WPCreated(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); connect(myMap,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SLOT(refreshOverlays())); @@ -46,13 +46,20 @@ pathPlanManager::~pathPlanManager() } void pathPlanManager::on_WPDeleted(int wp_numberint,WayPointItem * wp) { + QMutexLocker locker(&wplistmutex); + if(wp_numberint<0) + return; waypoints->removeOne(wp); } void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) { - qDebug()<<"pathplanner waypoint added"; + if(waypoints->contains(wp)) + return; + wplistmutex.lock(); waypoints->append(wp); + wplistmutex.unlock(); + wp->setWPType(WayPointItem::relative); customData data; data.mode=PathAction::MODE_FLYENDPOINT; data.condition=PathAction::ENDCONDITION_NONE; @@ -61,24 +68,16 @@ void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) refreshOverlays(); } -void pathPlanManager::on_WPNumberChanged(int oldNumber, int newNumber, WayPointItem * wp) -{ -} - void pathPlanManager::on_WPValuesChanged(WayPointItem * wp) { } -//typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, -//MODE_FLYCIRCLELEFT=3, MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, -//MODE_DRIVECIRCLERIGHT=7, MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; void pathPlanManager::refreshOverlays() { + QMutexLocker locker(&wplistmutex); myMap->deleteAllOverlays(); - qDebug()<<"foreach start"; foreach(WayPointItem * wp,*waypoints) { - qDebug()<<"wp:"<Number(); customData data=wp->customData().value(); switch(data.mode) { @@ -86,7 +85,6 @@ void pathPlanManager::refreshOverlays() case PathAction::MODE_FLYVECTOR: case PathAction::MODE_DRIVEENDPOINT: case PathAction::MODE_DRIVEVECTOR: - qDebug()<<"addline"; if(wp->Number()==0) myMap->WPLineCreate((HomeItem*)myMap->Home,wp); else @@ -105,11 +103,12 @@ void pathPlanManager::refreshOverlays() } } - qDebug()<<"foreach end"; } WayPointItem * pathPlanManager::findWayPointNumber(int number) { + if(number<0) + return NULL; foreach(WayPointItem * wp,*waypoints) { if(wp->Number()==number) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h index 4f58b25e6..0868d44eb 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h @@ -32,6 +32,8 @@ #include "opmapcontrol/opmapcontrol.h" #include "pathaction.h" #include "waypoint.h" +#include "QMutexLocker" +#include "QPointer" namespace mapcontrol { struct customData @@ -63,12 +65,12 @@ private slots: void refreshOverlays(); void on_WPDeleted(int wp_numberint, WayPointItem *); void on_WPInserted(int,WayPointItem*); - void on_WPNumberChanged(int,int,WayPointItem*); void on_WPValuesChanged(WayPointItem*); private: Ui::pathPlanManager *ui; OPMapWidget * myMap; - QList * waypoints; + QList > * waypoints; + QMutex wplistmutex; }; #endif // PATHPLANMANAGER_H From 5da9efd673c7fa9556fe871ec8c9f719b7d7ed5b Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 6 Jun 2012 20:51:04 +0100 Subject: [PATCH 016/116] GCS/MapLib - Several fixes, changes and enhancements. --- .../src/libs/opmapcontrol/opmapcontrol.h | 19 + .../src/mapwidget/images/waypoint_marker1.png | Bin 0 -> 4359 bytes .../src/mapwidget/images/waypoint_marker2.png | Bin 0 -> 4385 bytes .../src/mapwidget/images/waypoint_marker3.png | Bin 0 -> 1613 bytes .../src/mapwidget/mapgraphicitem.cpp | 3 + .../src/mapwidget/mapresources.qrc | 3 + .../src/mapwidget/waypointcircle.cpp | 32 +- .../src/mapwidget/waypointcircle.h | 2 +- .../src/mapwidget/waypointitem.cpp | 16 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 4 +- .../src/plugins/config/configgadgetwidget.h | 2 - .../openpilotgcs/src/plugins/opmap/opmap.pro | 2 +- .../opmap/opmap_edit_waypoint_dialog.cpp | 284 ++++-- .../opmap/opmap_edit_waypoint_dialog.h | 21 +- .../opmap/opmap_edit_waypoint_dialog.ui | 842 ++++++++++++------ .../plugins/opmap/opmap_overlay_widget.cpp | 2 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 88 +- .../src/plugins/opmap/opmapgadgetwidget.h | 18 +- .../src/plugins/opmap/pathplanmanager.cpp | 14 +- .../src/plugins/opmap/pathplanmanager.h | 15 - 20 files changed, 913 insertions(+), 454 deletions(-) create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker1.png create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker2.png create mode 100644 ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker3.png diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/opmapcontrol.h b/ground/openpilotgcs/src/libs/opmapcontrol/opmapcontrol.h index 4add132fd..aae8fd5ff 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/opmapcontrol.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/opmapcontrol.h @@ -1 +1,20 @@ +#ifndef OPMAP_CONTROL_H_ +#define OPMAP_CONTROL_H_ #include "src/mapwidget/opmapwidget.h" +namespace mapcontrol +{ + struct customData + { + float velocity; + int mode; + float mode_params[4]; + int condition; + float condition_params[4]; + int command; + int jumpdestination; + int errordestination; + }; + +} +Q_DECLARE_METATYPE(mapcontrol::customData) +#endif diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker1.png b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker1.png new file mode 100644 index 0000000000000000000000000000000000000000..179be20075e5c973c890e292034df9d521820aae GIT binary patch literal 4359 zcmV+i5%}(jP)KLZ*U+IBfRsybQWXdwQbLP>6pAqfylh#{fb6;Z(vMMVS~$e@S=j*ftg6;Uhf59&ghTmgWD0l;*T zI709Y^p6lP1rIRMx#05C~cW=H_Aw*bJ-5DT&Z2n+x)QHX^p z00esgV8|mQcmRZ%02D^@S3L16t`O%c004NIvOKvYIYoh62rY33S640`D9%Y2D-rV&neh&#Q1i z007~1e$oCcFS8neI|hJl{-P!B1ZZ9hpmq0)X0i`JwE&>$+E?>%_LC6RbVIkUx0b+_+BaR3cnT7Zv!AJxW zizFb)h!jyGOOZ85F;a?DAXP{m@;!0_IfqH8(HlgRxt7s3}k3K`kFu>>-2Q$QMFfPW!La{h336o>X zu_CMttHv6zR;&ZNiS=X8v3CR#fknUxHUxJ0uoBa_M6WNWeqIg~6QE69c9o#eyhGvpiOA@W-aonk<7r1(?fC{oI5N*U!4 zfg=2N-7=cNnjjOr{yriy6mMFgG#l znCF=fnQv8CDz++o6_Lscl}eQ+l^ZHARH>?_s@|##Rr6KLRFA1%Q+=*RRWnoLsR`7U zt5vFIcfW3@?wFpwUVxrVZ>QdQz32KIeJ}k~{cZZE^+ya? z2D1z#2HOnI7(B%_ac?{wFUQ;QQA1tBKtrWrm0_3Rgps+?Jfqb{jYbcQX~taRB;#$y zZN{S}1|}gUOHJxc?wV3fxuz+mJ4`!F$IZ;mqRrNsHJd##*D~ju=bP7?-?v~|cv>vB zsJ6IeNwVZxrdjT`yl#bBIa#GxRa#xMMy;K#CDyyGyQdMSxlWT#tDe?p!?5wT$+oGt z8L;Kp2HUQ-ZMJ=3XJQv;x5ci*?vuTfeY$;({XGW_huIFR9a(?@3)XSs8O^N5RyOM=TTmp(3=8^+zpz2r)C z^>JO{deZfso3oq3?Wo(Y?l$ge?uXo;%ru`Vo>?<<(8I_>;8Eq#KMS9gFl*neeosSB zfoHYnBQIkwkyowPu(zdms`p{<7e4kra-ZWq<2*OsGTvEV%s0Td$hXT+!*8Bnh2KMe zBmZRodjHV?r+_5^X9J0WL4jKW`}lf%A-|44I@@LTvf1rHjG(ze6+w@Jt%Bvjts!X0 z?2xS?_ve_-kiKB_KiJlZ$9G`c^=E@oNG)mWWaNo-3TIW8)$Hg0Ub-~8?KhvJ>$ z3*&nim@mj(aCxE5!t{lw7O5^0EIO7zOo&c6l<+|iDySBWCGrz@C5{St!X3hAA}`T4 z(TLbXTq+(;@<=L8dXnssyft|w#WSTW<++3>sgS%(4NTpeI-VAqb|7ssJvzNHgOZVu zaYCvgO_R1~>SyL=cFU|~g|hy|Zi}}s9+d~lYqOB71z9Z$wnC=pR9Yz4DhIM>Wmjgu z&56o6maCpC&F##y%G;1PobR9i?GnNg;gYtchD%p19a!eQtZF&3JaKv33gZ<8D~47E ztUS1iwkmDaPpj=$m#%)jCVEY4fnLGNg2A-`YwHVD3gv};>)hAvT~AmqS>Lr``i7kw zJ{5_It`yrBmlc25DBO7E8;5VoznR>Ww5hAaxn$2~(q`%A-YuS64wkBy=9dm`4cXeX z4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC-q*U}&`cyXV(%rRT*Z6MH?i+i& z_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-Nmiuj8txj!m?Z*Ss1N{dh4z}01 z)YTo*JycSU)+_5r4#yw9{+;i4Ee$peRgIj+;v;ZGdF1K$3E%e~4LaI(jC-u%2h$&R z9cLXcYC@Xwnns&bn)_Q~Te?roKGD|d-g^8;+aC{{G(1^(O7m37Y1-+6)01cN&y1aw zoqc{T`P^XJqPBbIW6s}d4{z_f5Om?vMgNQEJG?v2T=KYd^0M3I6IZxbny)%vZR&LD zJpPl@Psh8QyPB@KTx+@RdcC!KX7}kEo;S|j^u2lU7XQ}Oo;f|;z4Ll+_r>@1-xl3| zawq-H%e&ckC+@AhPrP6BKT#_XdT7&;F71j}Joy zkC~6lh7E@6o;W@^IpRNZ{ptLtL(gQ-CY~4mqW;US7Zxvm_|@yz&e53Bp_lTPlfP|z zrTyx_>lv@x#=^!PzR7qqF<$gm`|ZJZ+;<)Cqu&ot2z=00004XF*Lt006O$eEU(80000WV@Og>004R=004l4008;_004mL004C` z008P>0026e000+nl3&F}000IeNkl7-k6~}+~zIh)rwx8|9&&E!mm_%un z29Xp|Dm4qBNZG)mfwDtLpdztDAb}8+k43v;SBXVn5d?xJ4XP+rR6rFxpP=d5}CA3=-JHX>No#$?*E)~)#1a3*|TR4b8~Z)%VmNfpxJD) zwzl@b>gwv}uU)(LiPhEBDtUOo0`NCr89+qX8rI&udzqh~XJllAD2fQf(9v3dzf>xH zYy0?kZEn}cIJm7!==Qu~BAw(g>F_;t-=wgwIQjBC7wXqSN{oLa`Ha9a3yr`6_0%!oG)c3}0 z`@sI4J46=>5C+g~LwgfC&0Jv+fH4%breYNs)f&gL`1YqCk(y&a1Uv(vMPwHE#z)4- zC>9EeFoaGEHXG1tLBF5>V3;5xXr(A>jcr-jN;5HHt1s-H2l$#&YTkgqob5F17Qe*ex70&aOCU)KmF&McP#O@!tK+#*=%;N-@JLN_#tEllm?~v%0s)~1$yeiU5E&2CL|^!Hijq};>IyR z-)b}(|K3UALs^GcUWP%P$ZmAV6qjbV@^w8D^99JA5)#kY*6cv5Qw!H;z|sO&+u{hBQq* z;P6YAm)F1gyFVzB7_`oTr7~!Z5g|$qZXB~2gfzmKUoTu#7h0Vb@T7=z?(}k{QUSOO zeDU{}uJ)h(>)$~a@|4RtaA-2TWJoKBXe0@Ly1dNUMl%8qi^#%l7ibY-baWKQaRA-| zzWL+RXLw`fI+RN}P-&9P(2HX>*(u-`cl%U_VTgz@IXTIW9XptrnW0*(K6AC# zcTZfpqOdH;46!k|X~r8j*SXqt0eCh_tIuzSv3I7vro<|c04tpy zE4jMo->=7Ynx=$di065T2-Rwpsi`R@CMN2YO6BE0U#lY`7_Io%+6I!Z(Z9Se5Fkks zJkKMFB1)wa6B83mPEO)D&WQ`{9^HYDWEtn0ZGe~WHH9n@!5Bjj1o*y>Qi{>hQ7p?s zDfL>X({bP4Y>jKBxH<3uPTmuEd;2Fzg75pJX-c_V#q$z`?QlPJ{{y_8b`(VzV-OLtEW;SHdZX8)+vx#Z`oDny!{LxH3`vrNLZLtq z1h}r-TD-Z2Ne#e_4+Pxm$uv#rcDpp2%|Vz9<<^4he<0v(`?#)45Ck+D4eIr}3k1Lj z(EdO`5yA63TCEl$LcLyReSO^p)&U!6-VgZS0RS0jkiDfM6OaG^002ovPDHLkV1mo@ BB#Qt5 literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker2.png b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/images/waypoint_marker2.png new file mode 100644 index 0000000000000000000000000000000000000000..7834aa5435a3297aff43f2df126b28a9040608c2 GIT binary patch literal 4385 zcmV++5#H{JP)KLZ*U+IBfRsybQWXdwQbLP>6pAqfylh#{fb6;Z(vMMVS~$e@S=j*ftg6;Uhf59&ghTmgWD0l;*T zI709Y^p6lP1rIRMx#05C~cW=H_Aw*bJ-5DT&Z2n+x)QHX^p z00esgV8|mQcmRZ%02D^@S3L16t`O%c004NIvOKvYIYoh62rY33S640`D9%Y2D-rV&neh&#Q1i z007~1e$oCcFS8neI|hJl{-P!B1ZZ9hpmq0)X0i`JwE&>$+E?>%_LC6RbVIkUx0b+_+BaR3cnT7Zv!AJxW zizFb)h!jyGOOZ85F;a?DAXP{m@;!0_IfqH8(HlgRxt7s3}k3K`kFu>>-2Q$QMFfPW!La{h336o>X zu_CMttHv6zR;&ZNiS=X8v3CR#fknUxHUxJ0uoBa_M6WNWeqIg~6QE69c9o#eyhGvpiOA@W-aonk<7r1(?fC{oI5N*U!4 zfg=2N-7=cNnjjOr{yriy6mMFgG#l znCF=fnQv8CDz++o6_Lscl}eQ+l^ZHARH>?_s@|##Rr6KLRFA1%Q+=*RRWnoLsR`7U zt5vFIcfW3@?wFpwUVxrVZ>QdQz32KIeJ}k~{cZZE^+ya? z2D1z#2HOnI7(B%_ac?{wFUQ;QQA1tBKtrWrm0_3Rgps+?Jfqb{jYbcQX~taRB;#$y zZN{S}1|}gUOHJxc?wV3fxuz+mJ4`!F$IZ;mqRrNsHJd##*D~ju=bP7?-?v~|cv>vB zsJ6IeNwVZxrdjT`yl#bBIa#GxRa#xMMy;K#CDyyGyQdMSxlWT#tDe?p!?5wT$+oGt z8L;Kp2HUQ-ZMJ=3XJQv;x5ci*?vuTfeY$;({XGW_huIFR9a(?@3)XSs8O^N5RyOM=TTmp(3=8^+zpz2r)C z^>JO{deZfso3oq3?Wo(Y?l$ge?uXo;%ru`Vo>?<<(8I_>;8Eq#KMS9gFl*neeosSB zfoHYnBQIkwkyowPu(zdms`p{<7e4kra-ZWq<2*OsGTvEV%s0Td$hXT+!*8Bnh2KMe zBmZRodjHV?r+_5^X9J0WL4jKW`}lf%A-|44I@@LTvf1rHjG(ze6+w@Jt%Bvjts!X0 z?2xS?_ve_-kiKB_KiJlZ$9G`c^=E@oNG)mWWaNo-3TIW8)$Hg0Ub-~8?KhvJ>$ z3*&nim@mj(aCxE5!t{lw7O5^0EIO7zOo&c6l<+|iDySBWCGrz@C5{St!X3hAA}`T4 z(TLbXTq+(;@<=L8dXnssyft|w#WSTW<++3>sgS%(4NTpeI-VAqb|7ssJvzNHgOZVu zaYCvgO_R1~>SyL=cFU|~g|hy|Zi}}s9+d~lYqOB71z9Z$wnC=pR9Yz4DhIM>Wmjgu z&56o6maCpC&F##y%G;1PobR9i?GnNg;gYtchD%p19a!eQtZF&3JaKv33gZ<8D~47E ztUS1iwkmDaPpj=$m#%)jCVEY4fnLGNg2A-`YwHVD3gv};>)hAvT~AmqS>Lr``i7kw zJ{5_It`yrBmlc25DBO7E8;5VoznR>Ww5hAaxn$2~(q`%A-YuS64wkBy=9dm`4cXeX z4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC-q*U}&`cyXV(%rRT*Z6MH?i+i& z_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-Nmiuj8txj!m?Z*Ss1N{dh4z}01 z)YTo*JycSU)+_5r4#yw9{+;i4Ee$peRgIj+;v;ZGdF1K$3E%e~4LaI(jC-u%2h$&R z9cLXcYC@Xwnns&bn)_Q~Te?roKGD|d-g^8;+aC{{G(1^(O7m37Y1-+6)01cN&y1aw zoqc{T`P^XJqPBbIW6s}d4{z_f5Om?vMgNQEJG?v2T=KYd^0M3I6IZxbny)%vZR&LD zJpPl@Psh8QyPB@KTx+@RdcC!KX7}kEo;S|j^u2lU7XQ}Oo;f|;z4Ll+_r>@1-xl3| zawq-H%e&ckC+@AhPrP6BKT#_XdT7&;F71j}Joy zkC~6lh7E@6o;W@^IpRNZ{ptLtL(gQ-CY~4mqW;US7Zxvm_|@yz&e53Bp_lTPlfP|z zrTyx_>lv@x#=^!PzR7qqF<$gm`|ZJZ+;<)Cqu&ot2z=00004XF*Lt006O$eEU(80000WV@Og>004R=004l4008;_004mL004C` z008P>0026e000+nl3&F}000I&Nkl1JR`E+qF7f-;l|@($IrM&}j?in|N(cUzuCs(D51Z%Og`XI_`Pkb6V?*H-WF|QyAn3@V5u} zCkBz@53orWNCdQj7C08v+oVfvoH(Hqr_5EC`OfnboIF=+0uO1e&jH9HCK6dRFb-{H z95_754}Nv>W+Z+%+X7(!lY7W!1UVx^2I%iEh|vutsP1=&`*!(Wxd;nkY^QV@2Rablm`8HCvy#{*T5vMdz+@Diqg% zMiz`LPd&OD;BA+ZC`Aw^I9`k$#I!oDZnRwioXa*YE&auAuGWs-IW+d!Pw$2_Tmu$z zjBOrZ{}X%I|D^|d#{`uq{77MY5ti-K2@_6FH$)Js72t%l7FVvow4cCZ##escQcr3+7d<)Bb? zOA{-|8&J$cJ_k~uQ%$T=Tt8u@>(j72mMveuc=Up>oS@p9JV+HQk}z?AeJ@X3s(s;W zzZG}^WF(jcF!PX+s5B*r6kRu<+3~1%Lw^10lsG@zY5||oTDNcZa-qKnFatdDyJOR< z&;0Z#WHL}Rpj3dYBu-KsFQR4n)V+}3Ps}hm(+GflTI;DBDUdqV^lj|Ntdsyw17H6B z&rk5isjE=RLtg=eBuW$=C#2~{OikDIA5K*PzNxi-{nl8?!1gH)m<+#ng#O_&LW&oq zk@?Mce|Cb%jWoF|070baxB)H8QOYBg zr!UvK-NS#L7UZ*_6k(ju4O8BjTHx|x2jF|})IrkgxCFM3Q7{<3bA-`d<80VEe62WO z9(dvSMM5Xi#ELLf*j~WITk`;~0)Kl)VCV!mEt|-TFb7MF>=2A*qn1Lx$K zd7<+eBA~ipQC)NQ+`IL-Oriw8>*1`dqEk(Iq{7B+o2ZNpEfmVdBY%AJ8amaejNr|) zHT2pV{nNVw0U|%dY1ss}PtMFy85?A9dIy-gcS5`ER)R}2q|7~&#!dPTy73XDOhaU0I#hJ1kkA_@*~`~LlP$B`|@P-SyGj@ z{H}lYpI4Um4463*mDYPN2i83@KoZ7ymP_P^WOD|^vWZzKVOC0$SK1!uW|slZ_9pTA z4gpe?64*YW69SMka}@du6v~D3H7~(iZ1KO`{RdE|n#hX?Y#$XTXstzc>Z4l#4` zF=$W;$ym01h8t+o7BS2=3Fwg1#NThu@hu=t@e0;YRyt+HC1~Es5zc`ruO)>6y~0O9 z?g%igs;&}qUY`oAjZCaXE!g?hd|_6D)4PzMf!nt`-eBhKH45MSw8EL=0yG047e}TDu(NLuQu16uM#ttMYCrs| zWC>|FBYB^9ibn)yY1nhAGHOQaicWzHW(N?YXELzEg&1cx`54%j7;BF)`Q_m{1W^2} zRinnBZ0a(DA!W0o)%^|>2rj{T*LEeSEJ`dMOLZ5{$yCdgN-CAz=WVLL4G21p13@BL zu$)6iLbjH!W_!vVx_gsuuD?c8)Oy)-NC!Htduc7v-uByyf{K?|CKS%hSyYUgZZTpA zUeYBNZ)t2U$E-8Ye!OJHYxVEQov|2n@8r12=k14wLT>|2+ zP>Mt5txQ*G-yiQ?r0eCYF47ox1u7}oRwMuzQiSyq<_P6dc`6JVZsc$Vm%n8x`jm3g zg2{JAkLs7d_~onmrQWfybq z)q!skk?o&+E>Lamdf8`cg{4iFOf|!Hj9C#X-ZH6oXH4*{guv^0!{mgQwQAWzS2$j| zx@T11)AprI6D$D=aBPB!GinV}HkqUA-zRDGWUd4v40dT;V+DG98@SuUD*ivmvFY?1 zgLGU!BGUy!fJ0mOJ7L5qek$({9Y|yS`wVtsa$6}peMzhJP-woF{0$n|{G@oq4{cjd z!Z|K0DHkGLc)S#`XkdRr*oJeAPw)PJpDJdWDe@nWd#ZiHPt}jI>8GpPxbm3;@m7I; zM3K<+=)2+HbjoxWaqreUIY=?m7M>C0@hcRX=cAe>ehSXy`ac^rQ=4qg}8z za!AL0zi|9{M?h(tQJd_7BMn}&kXbJ95kH)Eu>*1^^rHe*M$71zOQiRr4z%lT9#^Ch&dSN zRzYJY&lIry(7mRRiiM6zWbktr6GQM8zIv4upTKq}*jky3`O~#%o!m8P%Om#$9JiHZ z$u@)pYDgIawAf`CyEA$rzLMGU#_lkUy*b<)P^N7-^6kK4V1V(Pg9PV7{gu61URjwB zogDcG0(7}1rtZjLi33`yH41Fm&48GBbU$|g1+1iv!eC&?5s1Q@?v3n~GR72^^*k`3 zOuNK@+(J&CN4#dsLNT*=;#7WY6QaR~0)%F;B3j5c6wFD=^_R2!yagIYy#8>2%mVg; zUP@X>SESAtF^modifiers() == Qt::ShiftModifier) { SetZoomToFitRect(SelectedArea()); + selectedArea=internals::RectLatLng::Empty; } } @@ -276,6 +277,8 @@ namespace mapcontrol { if(event->modifiers()&(Qt::ShiftModifier|Qt::ControlModifier)) this->setCursor(Qt::CrossCursor); + if(event->key()==Qt::Key_Escape) + selectedArea=internals::RectLatLng::Empty; QGraphicsItem::keyPressEvent(event); } void MapGraphicItem::keyReleaseEvent(QKeyEvent *event) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc index b7a0b985c..b7709e2cc 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapresources.qrc @@ -12,6 +12,9 @@ images/mapquad.png images/dragons1.jpg images/dragons2.jpeg + images/waypoint_marker1.png + images/waypoint_marker2.png + images/waypoint_marker3.png images/airplanepip.png diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index b61e073db..751d0788a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -38,14 +38,17 @@ WayPointCircle::WayPointCircle(WayPointItem *center, WayPointItem *radius,bool c connect(radius,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); connect(center,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); connect(radius,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + refreshLocations(); + } -WayPointCircle::WayPointCircle(HomeItem *center, WayPointItem *radius, bool clockwise, MapGraphicItem *map, QColor color):my_center(center), +WayPointCircle::WayPointCircle(HomeItem *radius, WayPointItem *center, bool clockwise, MapGraphicItem *map, QColor color):my_center(center), my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) { - connect(center,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); - connect(radius,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(radius,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + connect(radius,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); + connect(center,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(center,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + refreshLocations(); } int WayPointCircle::type() const @@ -53,21 +56,13 @@ int WayPointCircle::type() const // Enable the use of qgraphicsitem_cast with this item. return Type; } -QPainterPath WayPointCircle::shape() const -{ - QPainterPath path = QGraphicsEllipseItem::shape(); - path.addPolygon(arrowHead); - return path; -} + void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) { QPointF p1; QPointF p2; - p1=my_center->pos(); - p2=my_center->pos(); - QLineF line(my_radius->pos(),my_center->pos()); - p1.ry()=p1.ry()+line.length(); - p2.ry()=p2.ry()-line.length(); + p1=QPointF(line.p1().x(),line.p1().y()+line.length()); + p2=QPointF(line.p1().x(),line.p1().y()-line.length()); QPen myPen = pen(); myPen.setColor(myColor); qreal arrowSize = 10; @@ -75,10 +70,8 @@ void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *op QBrush brush=painter->brush(); painter->setBrush(myColor); double angle =0; - if(myClockWise) + if(!myClockWise) angle+=Pi; - if (line.dy() >= 0) - angle = (Pi) - angle; QPointF arrowP1 = p1 + QPointF(sin(angle + Pi / 3) * arrowSize, cos(angle + Pi / 3) * arrowSize); @@ -104,8 +97,9 @@ void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *op void WayPointCircle::refreshLocations() { - QLineF line(my_center->pos(),my_radius->pos()); + line=QLineF(my_center->pos(),my_radius->pos()); this->setRect(my_center->pos().x(),my_center->pos().y(),2*line.length(),2*line.length()); + this->update(); } void WayPointCircle::waypointdeleted() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h index 0f4ce7ce2..1c89fb798 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h @@ -47,7 +47,6 @@ public: WayPointCircle(WayPointItem * center, WayPointItem * radius,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); WayPointCircle(HomeItem * center, WayPointItem * radius,bool clockwise,MapGraphicItem * map,QColor color=Qt::green); int type() const; - QPainterPath shape() const; void setColor(const QColor &color) { myColor = color; } private: @@ -57,6 +56,7 @@ private: QPolygonF arrowHead; QColor myColor; bool myClockWise; + QLineF line; protected: void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); public slots: diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 9f6f87f6d..379d898a0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -297,8 +297,10 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals emit WPValuesChanged(this); if(value) picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png")); - else + else if(this->flags() & QGraphicsItem::ItemIsMovable==QGraphicsItem::ItemIsMovable) picture.load(QString::fromUtf8(":/markers/images/marker.png")); + else + picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); this->update(); } @@ -403,5 +405,17 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); } + void WayPointItem::setFlag(QGraphicsItem::GraphicsItemFlag flag, bool enabled) + { + if(flag==QGraphicsItem::ItemIsMovable) + { + if(enabled) + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + else + picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + } + QGraphicsItem::setFlag(flag,enabled); + } + int WayPointItem::snumber=0; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index e0bd594b5..aa9296f13 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -155,10 +155,9 @@ public: void RefreshPos(); void RefreshToolTip(); QPixmap picture; - QVariant customData(){return myCustomData;} - void setCustomData(QVariant arg){myCustomData=arg;} QString customString(){return myCustomString;} void setCustomString(QString arg){myCustomString=arg;} + void setFlag(GraphicsItemFlag flag, bool enabled); ~WayPointItem(); static int snumber; @@ -188,7 +187,6 @@ private: QTransform transf; HomeItem * myHome; wptype myType; - QVariant myCustomData; QString myCustomString; public slots: diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index e39cabfe8..3c7294eac 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -34,11 +34,9 @@ #include "objectpersistence.h" #include #include -//#include #include #include "utils/pathutils.h" #include -//#include "fancytabwidget.h" #include "utils/mytabbedstackwidget.h" #include "../uavobjectwidgetutils/configtaskwidget.h" diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index 61b200a97..af12afa25 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -1,6 +1,6 @@ +QT += webkit network TEMPLATE = lib TARGET = OPMapGadget - include(../../openpilotgcsplugin.pri) include(../../plugins/coreplugin/coreplugin.pri) include(../../libs/opmapcontrol/opmapcontrol.pri) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 2c7d20761..9d1761c5e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -27,8 +27,15 @@ #include "opmap_edit_waypoint_dialog.h" #include "ui_opmap_edit_waypoint_dialog.h" - +#include "opmapcontrol/opmapcontrol.h" // ********************************************************************* +typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, + MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, + MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; +typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, + ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, + ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; + // constructor opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent) : @@ -36,8 +43,33 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent) : ui(new Ui::opmap_edit_waypoint_dialog) { ui->setupUi(this); - waypoint_item = NULL; - connect(ui->rbRelative,SIGNAL(toggled(bool)),this,SLOT(setupWidgets(bool))); + my_waypoint = NULL; + connect(ui->rbRelative,SIGNAL(toggled(bool)),this,SLOT(setupPositionWidgets(bool))); + connect(ui->cbMode,SIGNAL(currentIndexChanged(int)),this,SLOT(setupModeWidgets())); + connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets())); + ui->cbMode->addItem("Fly Direct",MODE_FLYENDPOINT); + ui->cbMode->addItem("Fly Vector",MODE_FLYVECTOR); + ui->cbMode->addItem("Fly Circle Right",MODE_FLYCIRCLERIGHT); + ui->cbMode->addItem("Fly Circle Left",MODE_FLYCIRCLELEFT); + + ui->cbMode->addItem("Drive Direct",MODE_DRIVEENDPOINT); + ui->cbMode->addItem("Drive Vector",MODE_DRIVEVECTOR); + ui->cbMode->addItem("Drive Circle Right",MODE_DRIVECIRCLELEFT); + ui->cbMode->addItem("Drive Circle Left",MODE_DRIVECIRCLERIGHT); + + ui->cbMode->addItem("Fixed Attitude",MODE_FIXEDATTITUDE); + ui->cbMode->addItem("Set Accessory",MODE_SETACCESSORY); + ui->cbMode->addItem("Disarm Alarm",MODE_DISARMALARM); + + ui->cbCondition->addItem("None",ENDCONDITION_NONE); + ui->cbCondition->addItem("Timeout",ENDCONDITION_TIMEOUT); + ui->cbCondition->addItem("Distance to tgt",ENDCONDITION_DISTANCETOTARGET); + ui->cbCondition->addItem("Leg remaining",ENDCONDITION_LEGREMAINING); + ui->cbCondition->addItem("Above Altitude",ENDCONDITION_ABOVEALTITUDE); + ui->cbCondition->addItem("Pointing towards next",ENDCONDITION_POINTINGTOWARDSNEXT); + ui->cbCondition->addItem("Python script",ENDCONDITION_PYTHONSCRIPT); + ui->cbCondition->addItem("Immediate",ENDCONDITION_IMMEDIATE); + } // destrutor @@ -65,7 +97,7 @@ void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() int res = saveSettings(); if (res < 0) return; - waypoint_item = NULL; + my_waypoint = NULL; close(); } @@ -77,17 +109,10 @@ void opmap_edit_waypoint_dialog::on_pushButtonApply_clicked() void opmap_edit_waypoint_dialog::on_pushButtonRevert_clicked() { - ui->checkBoxLocked->setChecked(original_locked); - ui->spinBoxNumber->setValue(original_number); - ui->doubleSpinBoxLatitude->setValue(original_coord.Lat()); - ui->doubleSpinBoxLongitude->setValue(original_coord.Lng()); - ui->doubleSpinBoxAltitude->setValue(original_altitude); - ui->lineEditDescription->setText(original_description); - - saveSettings(); + loadFromWP(my_waypoint); } -void opmap_edit_waypoint_dialog::setupWidgets(bool isRelative) +void opmap_edit_waypoint_dialog::setupPositionWidgets(bool isRelative) { ui->lbLong->setVisible(!isRelative); ui->lbDegLong->setVisible(!isRelative); @@ -103,85 +128,216 @@ void opmap_edit_waypoint_dialog::setupWidgets(bool isRelative) ui->doubleSpinBoxBearing->setVisible(isRelative); } +void opmap_edit_waypoint_dialog::setupModeWidgets() +{ + ModeOptions mode=(ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + switch(mode) + { + case MODE_FLYENDPOINT: + case MODE_FLYVECTOR: + case MODE_FLYCIRCLERIGHT: + case MODE_FLYCIRCLELEFT: + case MODE_DRIVEENDPOINT: + case MODE_DRIVEVECTOR: + case MODE_DRIVECIRCLELEFT: + case MODE_DRIVECIRCLERIGHT: + case MODE_DISARMALARM: + ui->modeParam1->setVisible(false); + ui->modeParam2->setVisible(false); + ui->modeParam3->setVisible(false); + ui->modeParam4->setVisible(false); + ui->dsb_modeParam1->setVisible(false); + ui->dsb_modeParam2->setVisible(false); + ui->dsb_modeParam3->setVisible(false); + ui->dsb_modeParam4->setVisible(false); + break; + case MODE_FIXEDATTITUDE: + ui->modeParam1->setText("pitch"); + ui->modeParam2->setText("roll"); + ui->modeParam3->setText("yaw"); + ui->modeParam4->setText("throttle"); + ui->modeParam1->setVisible(true); + ui->modeParam2->setVisible(true); + ui->modeParam3->setVisible(true); + ui->modeParam4->setVisible(true); + ui->dsb_modeParam1->setVisible(true); + ui->dsb_modeParam2->setVisible(true); + ui->dsb_modeParam3->setVisible(true); + ui->dsb_modeParam4->setVisible(true); + break; + case MODE_SETACCESSORY: + ui->modeParam1->setText("Acc.channel"); + ui->modeParam2->setText("Value"); + ui->modeParam1->setVisible(true); + ui->modeParam2->setVisible(true); + ui->modeParam3->setVisible(false); + ui->modeParam4->setVisible(false); + ui->dsb_modeParam1->setVisible(true); + ui->dsb_modeParam2->setVisible(true); + ui->dsb_modeParam3->setVisible(false); + ui->dsb_modeParam4->setVisible(false); + break; + } +} +void opmap_edit_waypoint_dialog::setupConditionWidgets() +{ + EndConditionOptions mode=(EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + switch(mode) + { + case ENDCONDITION_NONE: + case ENDCONDITION_IMMEDIATE: + case ENDCONDITION_PYTHONSCRIPT: + ui->condParam1->setVisible(false); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(false); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + break; + case ENDCONDITION_TIMEOUT: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Timeout(ms)"); + break; + case ENDCONDITION_DISTANCETOTARGET: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(true); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(true); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Distance(m)"); + ui->condParam2->setText("Flag(0=2D,1=3D)");//FIXME + break; + case ENDCONDITION_LEGREMAINING: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); + break; + case ENDCONDITION_ABOVEALTITUDE: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Altitude in meters (negative)"); + break; + case ENDCONDITION_POINTINGTOWARDSNEXT: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Degrees variation allowed"); + break; + default: + + break; + } +} void opmap_edit_waypoint_dialog::on_pushButtonCancel_clicked() { - waypoint_item = NULL; + my_waypoint = NULL; close(); } -// ********************************************************************* - int opmap_edit_waypoint_dialog::saveSettings() { - // ******************** - // fetch the various ui item values - - bool locked = ui->checkBoxLocked->isChecked(); - int number = ui->spinBoxNumber->value(); if (number < 0) { return -1; } + customData data; + data.mode=ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + data.mode_params[0]=ui->dsb_modeParam1->value(); + data.mode_params[1]=ui->dsb_modeParam2->value(); + data.mode_params[2]=ui->dsb_modeParam3->value(); + data.mode_params[3]=ui->dsb_modeParam4->value(); - double latitude = ui->doubleSpinBoxLatitude->value(); - double longitude = ui->doubleSpinBoxLongitude->value(); + data.condition=ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + data.condition_params[0]=ui->dsb_condParam1->value(); + data.condition_params[1]=ui->dsb_condParam2->value(); + data.condition_params[2]=ui->dsb_condParam3->value(); + data.condition_params[3]=ui->dsb_condParam4->value(); - double altitude = ui->doubleSpinBoxAltitude->value(); + QVariant var; + var.setValue(data); + my_waypoint->setData(0,var); - QString description = ui->lineEditDescription->displayText().simplified(); - - // ******************** - // transfer the settings to the actual waypoint - - waypoint_item->SetNumber(number); - waypoint_item->SetCoord(internals::PointLatLng(latitude, longitude)); - waypoint_item->SetAltitude(altitude); - waypoint_item->SetDescription(description); - waypoint_item->setFlag(QGraphicsItem::ItemIsMovable, !locked); + my_waypoint->SetNumber(ui->spinBoxNumber->value()); + my_waypoint->SetCoord(internals::PointLatLng(ui->doubleSpinBoxLatitude->value(), ui->doubleSpinBoxLongitude->value())); + my_waypoint->SetAltitude(ui->doubleSpinBoxAltitude->value()); + my_waypoint->SetDescription(ui->lineEditDescription->displayText().simplified()); + my_waypoint->setFlag(QGraphicsItem::ItemIsMovable, !ui->checkBoxLocked->isChecked()); if(ui->rbAbsolute->isChecked()) - waypoint_item->setWPType(mapcontrol::WayPointItem::absolute); + my_waypoint->setWPType(mapcontrol::WayPointItem::absolute); else - waypoint_item->setWPType(mapcontrol::WayPointItem::relative); + my_waypoint->setWPType(mapcontrol::WayPointItem::relative); mapcontrol::distBearing pt; pt.distance=ui->spinBoxDistance->value(); pt.bearing=ui->doubleSpinBoxBearing->value()/180*M_PI; - this->waypoint_item->setRelativeCoord(pt); - // ******************** - + my_waypoint->setRelativeCoord(pt); return 0; // all ok } -// ********************************************************************* -// public functions +void opmap_edit_waypoint_dialog::loadFromWP(mapcontrol::WayPointItem *waypoint_item) +{ + customData data=waypoint_item->data(0).value(); + ui->spinBoxNumber->setValue(waypoint_item->Number()); + ui->doubleSpinBoxLatitude->setValue(waypoint_item->Coord().Lat()); + ui->doubleSpinBoxLongitude->setValue(waypoint_item->Coord().Lng()); + ui->doubleSpinBoxAltitude->setValue(waypoint_item->Altitude()); + ui->lineEditDescription->setText(waypoint_item->Description()); + if(waypoint_item->WPType()==mapcontrol::WayPointItem::absolute) + ui->rbAbsolute->setChecked(true); + else + ui->rbRelative->setChecked(true); + ui->doubleSpinBoxBearing->setValue(waypoint_item->getRelativeCoord().bearing*180/M_PI); + ui->spinBoxDistance->setValue(waypoint_item->getRelativeCoord().distance); + + ui->cbMode->setCurrentIndex(ui->cbMode->findData(data.mode)); + ui->dsb_modeParam1->setValue(data.mode_params[0]); + ui->dsb_modeParam2->setValue(data.mode_params[1]); + ui->dsb_modeParam3->setValue(data.mode_params[2]); + ui->dsb_modeParam4->setValue(data.mode_params[3]); + + ui->cbCondition->setCurrentIndex(ui->cbCondition->findData(data.condition)); + ui->dsb_condParam1->setValue(data.condition_params[0]); + ui->dsb_condParam2->setValue(data.condition_params[1]); + ui->dsb_condParam3->setValue(data.condition_params[2]); + ui->dsb_condParam4->setValue(data.condition_params[3]); +} void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) return; - this->waypoint_item = waypoint_item; - - original_number = this->waypoint_item->Number(); - original_locked = (this->waypoint_item->flags() & QGraphicsItem::ItemIsMovable) == 0; - original_coord = this->waypoint_item->Coord(); - original_altitude = this->waypoint_item->Altitude(); - original_description = this->waypoint_item->Description().simplified(); - original_type=this->waypoint_item->WPType(); - original_distance=this->waypoint_item->getRelativeCoord().distance; - original_bearing=this->waypoint_item->getRelativeCoord().bearing*180/M_PI; - ui->checkBoxLocked->setChecked(original_locked); - ui->spinBoxNumber->setValue(original_number); - ui->doubleSpinBoxLatitude->setValue(original_coord.Lat()); - ui->doubleSpinBoxLongitude->setValue(original_coord.Lng()); - ui->doubleSpinBoxAltitude->setValue(original_altitude); - ui->lineEditDescription->setText(original_description); - if(original_type==mapcontrol::WayPointItem::absolute) - ui->rbAbsolute->setChecked(true); - else - ui->rbRelative->setChecked(true); - ui->doubleSpinBoxBearing->setValue(original_bearing); - ui->spinBoxDistance->setValue(original_distance); - setupWidgets(ui->rbRelative->isChecked()); + this->my_waypoint = waypoint_item; + loadFromWP(waypoint_item); + setupPositionWidgets(ui->rbRelative->isChecked()); show(); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index b6fde4828..0270afa3d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -35,6 +35,7 @@ namespace Ui { class opmap_edit_waypoint_dialog; } +using namespace mapcontrol; class opmap_edit_waypoint_dialog : public QDialog { @@ -50,31 +51,21 @@ public: */ void editWaypoint(mapcontrol::WayPointItem *waypoint_item); + void loadFromWP(mapcontrol::WayPointItem *waypoint_item); protected: void changeEvent(QEvent *e); private: Ui::opmap_edit_waypoint_dialog *ui; - - int original_number; - bool original_locked; - internals::PointLatLng original_coord; - double original_altitude; - QString original_description; - double original_distance; - double original_bearing; - - - mapcontrol::WayPointItem::wptype original_type; - - mapcontrol::WayPointItem *waypoint_item; - + mapcontrol::WayPointItem * my_waypoint; int saveSettings(); private slots: private slots: - void setupWidgets(bool isRelative); + void setupModeWidgets(); + void setupPositionWidgets(bool isRelative); + void setupConditionWidgets(); void on_pushButtonCancel_clicked(); void on_pushButtonRevert_clicked(); void on_pushButtonApply_clicked(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index 84de38a2d..f77fcc965 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -9,8 +9,8 @@ 0 0 - 546 - 261 + 571 + 375 @@ -31,258 +31,604 @@ - - - - - - 0 - 0 - - - - Number - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 2 + + + + Position + + + + + 0 + 10 + 528 + 266 + + + + + + + 0 + 0 + + + + Latitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + true + + + + 0 + 0 + + + + Longitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Altitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + meters + + + + + + + + 0 + 0 + + + + Description + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 200 + + + + + + + + 0 + 0 + + + + 7 + + + -90.000000000000000 + + + 90.000000000000000 + + + + + + + 7 + + + -180.000000000000000 + + + 180.000000000000000 + + + + + + + -5000.000000000000000 + + + 5000.000000000000000 + + + + + + + degrees + + + + + + + degrees + + + + + + + + 0 + 0 + + + + Type + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Relative + + + + + + + Absolute + + + + + + + 999999999 + + + + + + + meters + + + + + + + degrees + + + + + + + Bearing + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 360.000000000000000 + + + + + + + + 0 + 0 + + + + Distance + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::LeftToRight + + + Locked + + + + + + + Number + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + - - - - - - 0 - 0 - - - - Latitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + Mode + + + + + -1 + -1 + 511 + 281 + + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Qt::LeftToRight + + + Mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 999999999.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param4 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - - true - - - - 0 - 0 - - - - Longitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + End condition + + + + + 0 + 0 + 551 + 291 + + + + QLayout::SetDefaultConstraint + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Qt::LeftToRight + + + Condition + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 999999999.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param4 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + - - - - - - 0 - 0 - - - - Altitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - meters - - - - - - - - 0 - 0 - - - - Description - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - Qt::RightToLeft - - - Locked - - - - - - - 200 - - - - - - - - 0 - 0 - - - - 7 - - - -90.000000000000000 - - - 90.000000000000000 - - - - - - - 7 - - - -180.000000000000000 - - - 180.000000000000000 - - - - - - - -5000.000000000000000 - - - 5000.000000000000000 - - - - - - - degrees - - - - - - - degrees - - - - - - - - 0 - 0 - - - - Type - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Relative - - - - - - - Absolute - - - - - - - 999999999 - - - - - - - meters - - - - - - - degrees - - - - - - - Bearing - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 360.000000000000000 - - - - - - - - 0 - 0 - - - - Distance - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - + + + + Page + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp index 4c7f7aeab..ac056f36b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp @@ -32,7 +32,7 @@ opmap_overlay_widget::opmap_overlay_widget(QWidget *parent) : QWidget(parent), ui(new Ui::opmap_overlay_widget) { - ui->setupUi(this); + } opmap_overlay_widget::~opmap_overlay_widget() diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 3dabcd91e..4fd28242c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -206,14 +206,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals - connect(m_map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals - connect(m_map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed - connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed - connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals - // connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); - // connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); - // connect(m_map, SIGNAL(WPDeleted(int,WayPointItem*)), this, SLOT(WPDeleted(int,WayPointItem*))); connect(m_map,SIGNAL(OnWayPointDoubleClicked(WayPointItem*)),this,SLOT(wpDoubleClickEvent(WayPointItem*))); m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position @@ -490,7 +483,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) contextMenu.addSeparator()->setText(tr("Waypoints")); contextMenu.addAction(wayPointEditorAct); - contextMenu.addAction(addWayPointAct); + contextMenu.addAction(addWayPointActFromContextMenu); if (m_mouse_waypoint) { // we have a waypoint under the mouse @@ -701,10 +694,6 @@ void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level } -void OPMapGadgetWidget::OnMapDrag() -{ -} - void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) { if (!m_widget || !m_map) @@ -754,47 +743,6 @@ void OPMapGadgetWidget::OnTileLoadComplete() m_widget->progressBarMap->setVisible(false); } -void OPMapGadgetWidget::OnMapZoomChanged() -{ -} - -void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type) -{ - Q_UNUSED(type); -} - -void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos) -{ - Q_UNUSED(zoom); - Q_UNUSED(pos); -} - -void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumber, WayPointItem *waypoint) -{ - Q_UNUSED(oldnumber); - Q_UNUSED(newnumber); - Q_UNUSED(waypoint); -} - -/** - TODO: slot to do something upon Waypoint insertion - */ -void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint) -{ - Q_UNUSED(number); - Q_UNUSED(waypoint); -} - -/** - TODO: slot to do something upon Waypoint deletion - */ -void OPMapGadgetWidget::WPDeleted(int const &number, WayPointItem *waypoint) -{ - Q_UNUSED(number); - Q_UNUSED(waypoint); -} - - void OPMapGadgetWidget::on_toolButtonZoomP_clicked() { QMutexLocker locker(&m_map_mutex); @@ -1334,11 +1282,16 @@ void OPMapGadgetWidget::createActions() wayPointEditorAct->setEnabled(true); // temporary connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); - addWayPointAct = new QAction(tr("&Add waypoint"), this); - addWayPointAct->setShortcut(tr("Ctrl+A")); - addWayPointAct->setStatusTip(tr("Add waypoint")); - connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); - this->addAction(addWayPointAct); + addWayPointActFromContextMenu = new QAction(tr("&Add waypoint"), this); + addWayPointActFromContextMenu->setShortcut(tr("Ctrl+A")); + addWayPointActFromContextMenu->setStatusTip(tr("Add waypoint")); + connect(addWayPointActFromContextMenu, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggeredFromContextMenu())); + + addWayPointActFromThis = new QAction(tr("&Add waypoint"), this); + addWayPointActFromThis->setShortcut(tr("Ctrl+A")); + addWayPointActFromThis->setStatusTip(tr("Add waypoint")); + connect(addWayPointActFromThis, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggeredFromThis())); + this->addAction(addWayPointActFromThis); editWayPointAct = new QAction(tr("&Edit waypoint"), this); editWayPointAct->setShortcut(tr("Ctrl+E")); @@ -1738,8 +1691,16 @@ void OPMapGadgetWidget::onOpenWayPointEditorAct_triggered() { waypoint_editor_dialog.show(); } +void OPMapGadgetWidget::onAddWayPointAct_triggeredFromContextMenu() +{ + onAddWayPointAct_triggered(m_context_menu_lat_lon); +} +void OPMapGadgetWidget::onAddWayPointAct_triggeredFromThis() +{ + onAddWayPointAct_triggered(lastLatLngMouse); +} -void OPMapGadgetWidget::onAddWayPointAct_triggered() +void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) { if (!m_widget || !m_map) return; @@ -1747,20 +1708,11 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered() if (m_map_mode != Normal_MapMode) return; - // m_waypoint_list_mutex.lock(); - - // create a waypoint on the map at the last known mouse position - internals::PointLatLng coord; - if(this->contextMenu.isVisible()) - coord = m_context_menu_lat_lon; - else - coord=lastLatLngMouse; m_map->WPCreate(coord, 0, ""); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 50441b837..a2df40978 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -153,19 +153,8 @@ private slots: void OnCurrentPositionChanged(internals::PointLatLng point); void OnTileLoadComplete(); void OnTileLoadStart(); - void OnMapDrag(); - void OnMapZoomChanged(); - void OnMapTypeChanged(MapType::Types type); - void OnEmptyTileError(int zoom, core::Point pos); void OnTilesStillToLoad(int number); - /** - * Unused for now, hooks for future waypoint support - */ - void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); - void WPInserted(int const& number, WayPointItem* waypoint); - void WPDeleted(int const& number, WayPointItem* waypoint); - /** * @brief mouse right click context menu signals */ @@ -190,7 +179,9 @@ private slots: void onFollowUAVheadingAct_toggled(bool checked); void onOpenWayPointEditorAct_triggered(); - void onAddWayPointAct_triggered(); + void onAddWayPointAct_triggeredFromContextMenu(); + void onAddWayPointAct_triggeredFromThis(); + void onAddWayPointAct_triggered(internals::PointLatLng coord); void onEditWayPointAct_triggered(); void onLockWayPointAct_triggered(); void onDeleteWayPointAct_triggered(); @@ -280,7 +271,8 @@ private: QAction *followUAVheadingAct; QAction *wayPointEditorAct; - QAction *addWayPointAct; + QAction *addWayPointActFromThis; + QAction *addWayPointActFromContextMenu; QAction *editWayPointAct; QAction *lockWayPointAct; QAction *deleteWayPointAct; diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp index c4ac4f8e1..00a1734a3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp @@ -64,21 +64,25 @@ void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) data.mode=PathAction::MODE_FLYENDPOINT; data.condition=PathAction::ENDCONDITION_NONE; data.velocity=0; - wp->customData().setValue(data); + QVariant var; + var.setValue(data); + wp->setData(0,var); refreshOverlays(); } void pathPlanManager::on_WPValuesChanged(WayPointItem * wp) { } - +//typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, +//MODE_FLYCIRCLELEFT=3, MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, +//MODE_DRIVECIRCLERIGHT=7, MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; void pathPlanManager::refreshOverlays() { QMutexLocker locker(&wplistmutex); myMap->deleteAllOverlays(); foreach(WayPointItem * wp,*waypoints) { - customData data=wp->customData().value(); + customData data=wp->data(0).value(); switch(data.mode) { case PathAction::MODE_FLYENDPOINT: @@ -92,10 +96,14 @@ void pathPlanManager::refreshOverlays() break; case PathAction::MODE_FLYCIRCLERIGHT: case PathAction::MODE_DRIVECIRCLERIGHT: + if(wp->Number()==0) + myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,true); myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,true); break; case PathAction::MODE_FLYCIRCLELEFT: case PathAction::MODE_DRIVECIRCLELEFT: + if(wp->Number()==0) + myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,false); myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,false); break; default: diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h index 0868d44eb..c17e61441 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h @@ -34,22 +34,7 @@ #include "waypoint.h" #include "QMutexLocker" #include "QPointer" -namespace mapcontrol -{ - struct customData - { - float velocity; - int mode; - float mode_params[4]; - int condition; - float condition_params[4]; - int command; - int jumpdestination; - int errordestination; - }; -} -Q_DECLARE_METATYPE(mapcontrol::customData) namespace Ui { class pathPlanManager; } From 82b7f9f08d23ec90d854a16f1edc84173d12a9fc Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 14 Jun 2012 23:06:37 +0100 Subject: [PATCH 017/116] GCS/OPmap lib - changed the flight planner to a model view aproach --- .../src/mapwidget/opmapwidget.cpp | 58 + .../opmapcontrol/src/mapwidget/opmapwidget.h | 8 + .../src/mapwidget/waypointitem.cpp | 33 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 6 +- .../src/mapwidget/waypointline.cpp | 2 +- .../src/plugins/opmap/flightdatamodel.cpp | 583 ++++++++ .../src/plugins/opmap/flightdatamodel.h | 59 + .../opmap/images/Ekisho Deep Ocean HD1.png | Bin 0 -> 3263 bytes .../src/plugins/opmap/images/down_alt.png | Bin 0 -> 2256 bytes .../opmap/images/forward button white.png | Bin 0 -> 2937 bytes .../src/plugins/opmap/images/forward_alt.png | Bin 0 -> 2217 bytes .../src/plugins/opmap/images/new archive.png | Bin 0 -> 2670 bytes .../src/plugins/opmap/images/plus3.png | Bin 0 -> 2764 bytes .../opmap/images/rewind button white.png | Bin 0 -> 2932 bytes .../src/plugins/opmap/images/star.png | Bin 0 -> 2723 bytes .../src/plugins/opmap/images/stopb.png | Bin 0 -> 3221 bytes .../src/plugins/opmap/images/unarchive.png | Bin 0 -> 2996 bytes .../src/plugins/opmap/images/up_alt.png | Bin 0 -> 2208 bytes .../src/plugins/opmap/modelmapproxy.cpp | 270 ++++ .../src/plugins/opmap/modelmapproxy.h | 41 + .../openpilotgcs/src/plugins/opmap/opmap.pro | 19 +- .../openpilotgcs/src/plugins/opmap/opmap.qrc | 10 + .../opmap/opmap_edit_waypoint_dialog.cpp | 255 ++-- .../opmap/opmap_edit_waypoint_dialog.h | 19 +- .../opmap/opmap_edit_waypoint_dialog.ui | 1285 +++++++++-------- .../plugins/opmap/opmap_overlay_widget.cpp | 41 - .../src/plugins/opmap/opmap_overlay_widget.h | 49 - .../opmap/opmap_waypointeditor_dialog.cpp | 184 --- .../opmap/opmap_waypointeditor_dialog.h | 130 -- .../opmap/opmap_waypointeditor_dialog.ui | 248 ---- .../src/plugins/opmap/opmapgadgetwidget.cpp | 28 +- .../src/plugins/opmap/opmapgadgetwidget.h | 19 +- .../src/plugins/opmap/pathplanmanager.cpp | 126 -- .../src/plugins/opmap/pathplanmanager.h | 61 - .../src/plugins/opmap/pathplanmanager.ui | 21 - .../src/plugins/opmap/pathplanner.cpp | 93 ++ .../src/plugins/opmap/pathplanner.h | 45 + .../src/plugins/opmap/pathplanner.ui | 131 ++ .../src/plugins/opmap/widgetdelegates.cpp | 133 ++ .../src/plugins/opmap/widgetdelegates.h | 38 + 40 files changed, 2345 insertions(+), 1650 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/Ekisho Deep Ocean HD1.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/down_alt.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/forward button white.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/forward_alt.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/new archive.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/plus3.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/rewind button white.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/star.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/stopb.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/unarchive.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/up_alt.png create mode 100644 ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h delete mode 100644 ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp delete mode 100644 ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.h delete mode 100644 ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.cpp delete mode 100644 ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.h delete mode 100644 ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.ui delete mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp delete mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h delete mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanner.h create mode 100644 ground/openpilotgcs/src/plugins/opmap/pathplanner.ui create mode 100644 ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index f09859395..4186f73e8 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -55,6 +55,7 @@ namespace mapcontrol connect(map->core,SIGNAL(OnTileLoadStart()),this,SIGNAL(OnTileLoadStart())); connect(map->core,SIGNAL(OnTilesStillToLoad(int)),this,SIGNAL(OnTilesStillToLoad(int))); connect(map,SIGNAL(wpdoubleclicked(WayPointItem*)),this,SIGNAL(OnWayPointDoubleClicked(WayPointItem*))); + connect(&mscene,SIGNAL(selectionChanged()),this,SLOT(OnSelectionChanged())); SetShowDiagnostics(showDiag); this->setMouseTracking(followmouse); SetShowCompass(true); @@ -301,6 +302,37 @@ namespace mapcontrol emit WPDeleted(item->Number(),item); delete item; } + void OPMapWidget::WPDelete(int number) + { + foreach(QGraphicsItem* i,map->childItems()) + { + WayPointItem* w=qgraphicsitem_cast(i); + if(w) + { + if(w->Number()==number) + { + emit WPDeleted(w->Number(),w); + delete w; + return; + } + } + } + } + WayPointItem * OPMapWidget::WPFind(int number) + { + foreach(QGraphicsItem* i,map->childItems()) + { + WayPointItem* w=qgraphicsitem_cast(i); + if(w) + { + if(w->Number()==number) + { + return w; + } + } + } + return NULL; + } void OPMapWidget::WPSetVisibleAll(bool value) { foreach(QGraphicsItem* i,map->childItems()) @@ -378,6 +410,8 @@ namespace mapcontrol { connect(item,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),Qt::DirectConnection); connect(item,SIGNAL(WPValuesChanged(WayPointItem*)),this,SIGNAL(WPValuesChanged(WayPointItem*)),Qt::DirectConnection); + connect(item,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SIGNAL(WPLocalPositionChanged(QPointF,WayPointItem*)),Qt::DirectConnection); + connect(item,SIGNAL(manualCoordChange(WayPointItem*)),this,SIGNAL(WPManualCoordChange(WayPointItem*)),Qt::DirectConnection); connect(this,SIGNAL(WPInserted(int,WayPointItem*)),item,SLOT(WPInserted(int,WayPointItem*)),Qt::DirectConnection); connect(this,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),item,SLOT(WPRenumbered(int,int,WayPointItem*)),Qt::DirectConnection); connect(this,SIGNAL(WPDeleted(int,WayPointItem*)),item,SLOT(WPDeleted(int,WayPointItem*)),Qt::DirectConnection); @@ -438,4 +472,28 @@ namespace mapcontrol { new MapRipper(core,map->SelectedArea()); } + + void OPMapWidget::setSelectedWP(QListlist) + { + this->scene()->clearSelection(); + foreach(WayPointItem * wp,list) + { + wp->setSelected(true); + } + } + + void OPMapWidget::OnSelectionChanged() + { + QList list; + QList wplist; + list=this->scene()->selectedItems(); + foreach(QGraphicsItem* item,list) + { + WayPointItem * wp=qgraphicsitem_cast(item); + if(wp) + wplist.append(wp); + } + if(wplist.length()>0) + emit selectedWPChanged(wplist); + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 4da888bb1..b98b87ae1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -369,6 +369,9 @@ namespace mapcontrol void WPSetVisibleAll(bool value); WayPointItem *magicWPCreate(); bool WPPresent(); + void WPDelete(int number); + WayPointItem *WPFind(int number); + void setSelectedWP(QList list); private: internals::Core *core; MapGraphicItem *map; @@ -434,6 +437,9 @@ namespace mapcontrol * @param number number of the deleted WayPoint */ void WPDeleted(int const& number,WayPointItem* waypoint); + + void WPLocalPositionChanged(QPointF,WayPointItem*); + void WPManualCoordChange(WayPointItem*); /** * @brief Fires When a WayPoint is Reached * @@ -493,11 +499,13 @@ namespace mapcontrol */ void OnTilesStillToLoad(int number); void OnWayPointDoubleClicked(WayPointItem * waypoint); + void selectedWPChanged(QList); public slots: /** * @brief Ripps the current selection to the DB */ void RipMap(); + void OnSelectionChanged(); }; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 379d898a0..296aa10d0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -55,6 +55,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); } WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(false),description(""),shownumber(true),isDragging(false),altitude(0),map(map) @@ -95,6 +96,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); } WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { @@ -123,6 +125,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + qDebug()<<"Waypoint CTOR distance"<drawPixmap(-picture.width()/2,-picture.height(),picture); + painter->setPen(Qt::green); if(this->isSelected()) painter->drawRect(QRectF(-picture.width()/2,-picture.height(),picture.width()-1,picture.height()-1)); } @@ -220,7 +225,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals isDragging=false; RefreshToolTip(); - emit localPositionChanged(this->pos()); + emit manualCoordChange(this); + emit localPositionChanged(this->pos(),this); emit WPValuesChanged(this); } QGraphicsItem::mouseReleaseEvent(event); @@ -239,7 +245,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals QString relativeCoord_str = QString::number(relativeCoord.distance) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; text->setText(coord_str+"\n"+relativeCoord_str); textBG->setRect(text->boundingRect()); - emit localPositionChanged(this->pos()); + emit localPositionChanged(this->pos(),this); emit WPValuesChanged(this); } QGraphicsItem::mouseMoveEvent(event); @@ -266,10 +272,21 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } void WayPointItem::SetCoord(const internals::PointLatLng &value) { + if(this->WPType()==relative) + return; + bool abs_coord=false; + bool rel_coord=false; + if(coord!=value) + abs_coord=true; coord=value; + distBearing back=relativeCoord; + qDebug()<<"SET COORD"<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - emit WPValuesChanged(this); + if(back.distance!=relativeCoord.distance||back.bearing!=relativeCoord.bearing) + rel_coord=true; + if(abs_coord||rel_coord) + emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); this->update(); @@ -354,6 +371,12 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals RefreshToolTip(); this->update(); } + else + { + if(myHome) + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + emit WPValuesChanged(this); + } } void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) { @@ -388,7 +411,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals { core::Point point=map->FromLatLngToLocal(coord); this->setPos(point.X(),point.Y()); - emit localPositionChanged(this->pos()); + emit localPositionChanged(this->pos(),this); } void WayPointItem::RefreshToolTip() { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index aa9296f13..2bb8fe7ef 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -41,6 +41,8 @@ struct distBearing { double distance; double bearing; + double bearingToDegrees(){return bearing*180/M_PI;} + void setBearingFromDegrees(double degrees){bearing=degrees*M_PI/180;} }; class HomeItem; /** @@ -227,9 +229,11 @@ signals: * * @param waypoint a pointer to this WayPoint */ + void WPValuesChanged(WayPointItem* waypoint); void waypointdoubleclick(WayPointItem* waypoint); - void localPositionChanged(QPointF point); + void localPositionChanged(QPointF point,WayPointItem* waypoint); + void manualCoordChange(WayPointItem *); void aboutToBeDeleted(WayPointItem *); }; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 7ff8240a0..ddbcfd6d4 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -46,7 +46,7 @@ WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map { this->setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); connect(from,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); - connect(to,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(to,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); } int WayPointLine::type() const diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp new file mode 100644 index 000000000..a8c6508fa --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -0,0 +1,583 @@ +#include "flightdatamodel.h" +#include +#include +flightDataModel::flightDataModel(QObject *parent):QAbstractTableModel(parent) +{ + +} + +int flightDataModel::rowCount(const QModelIndex &/*parent*/) const +{ + return dataStorage.length(); +} + +int flightDataModel::columnCount(const QModelIndex &/*parent*/) const +{ + return 22; +} + +QVariant flightDataModel::data(const QModelIndex &index, int role) const +{ + if (role == Qt::DisplayRole||role==Qt::EditRole) + { + int rowNumber=index.row(); + int columnNumber=index.column(); + if(rowNumber>dataStorage.length()-1) + return QVariant(); + pathPlanData * myRow=dataStorage.at(rowNumber); + QVariant ret=getColumnByIndex(myRow,columnNumber); + return ret; + } + return QVariant(); +} +bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const QVariant value) +{ + switch(index) + { + case WPDESCRITPTION: + row->wpDescritption=value.toString(); + return true; + break; + case LATPOSITION: + row->latPosition=value.toDouble(); + return true; + break; + case LNGPOSITION: + row->lngPosition=value.toDouble(); + return true; + break; + case DISRELATIVE: + row->disRelative=value.toDouble(); + return true; + break; + case BEARELATIVE: + row->beaRelative=value.toDouble(); + return true; + break; + case ISRELATIVE: + row->isRelative=value.toDouble(); + return true; + break; + case ALTITUDE: + row->altitude=value.toDouble(); + return true; + break; + case VELOCITY: + row->velocity=value.toFloat(); + return true; + break; + case MODE: + row->mode=value.toInt(); + return true; + break; + case MODE_PARAMS0: + row->mode_params[0]=value.toInt(); + return true; + break; + case MODE_PARAMS1: + row->mode_params[1]=value.toInt(); + return true; + break; + case MODE_PARAMS2: + row->mode_params[2]=value.toInt(); + return true; + break; + case MODE_PARAMS3: + row->mode_params[3]=value.toInt(); + return true; + break; + case CONDITION: + row->condition=value.toInt(); + return true; + break; + case CONDITION_PARAMS0: + row->condition_params[0]=value.toInt(); + return true; + break; + case CONDITION_PARAMS1: + row->condition_params[1]=value.toInt(); + return true; + break; + case CONDITION_PARAMS2: + row->condition_params[2]=value.toInt(); + return true; + break; + case CONDITION_PARAMS3: + row->condition_params[3]=value.toInt(); + return true; + break; + case COMMAND: + row->command=value.toInt(); + break; + case JUMPDESTINATION: + row->jumpdestination=value.toInt(); + return true; + break; + case ERRORDESTINATION: + row->errordestination=value.toInt(); + return true; + break; + case LOCKED: + row->locked=value.toBool(); + return true; + break; + default: + return false; + } +} +QVariant flightDataModel::getColumnByIndex(const pathPlanData *row,const int index) const +{ + switch(index) + { + case WPDESCRITPTION: + return row->wpDescritption; + break; + case LATPOSITION: + return row->latPosition; + break; + case LNGPOSITION: + return row->lngPosition; + break; + case DISRELATIVE: + return row->disRelative; + break; + case BEARELATIVE: + return row->beaRelative; + break; + case ISRELATIVE: + return row->isRelative; + break; + case ALTITUDE: + return row->altitude; + break; + case VELOCITY: + return row->velocity; + break; + case MODE: + return row->mode; + break; + case MODE_PARAMS0: + return row->mode_params[0]; + break; + case MODE_PARAMS1: + return row->mode_params[1]; + break; + case MODE_PARAMS2: + return row->mode_params[2]; + break; + case MODE_PARAMS3: + return row->mode_params[3]; + break; + case CONDITION: + return row->condition; + break; + case CONDITION_PARAMS0: + return row->condition_params[0]; + break; + case CONDITION_PARAMS1: + return row->condition_params[1]; + break; + case CONDITION_PARAMS2: + return row->condition_params[2]; + break; + case CONDITION_PARAMS3: + return row->condition_params[3]; + break; + case COMMAND: + return row->command; + break; + case JUMPDESTINATION: + return row->jumpdestination; + break; + case ERRORDESTINATION: + return row->errordestination; + break; + case LOCKED: + return row->locked; + } +} +QVariant flightDataModel::headerData(int section, Qt::Orientation orientation, int role) const + { + if (role == Qt::DisplayRole) + { + if(orientation==Qt::Vertical) + { + return QString::number(section); + } + else if (orientation == Qt::Horizontal) { + switch (section) + { + case WPDESCRITPTION: + return QString("Description"); + break; + case LATPOSITION: + return QString("Latitude"); + break; + case LNGPOSITION: + return QString("Longitude"); + break; + case DISRELATIVE: + return QString("Distance to home"); + break; + case BEARELATIVE: + return QString("Bearing from home"); + break; + case ISRELATIVE: + return QString("Relative to home"); + break; + case ALTITUDE: + return QString("Altitude"); + break; + case VELOCITY: + return QString("Velocity"); + break; + case MODE: + return QString("Mode"); + break; + case MODE_PARAMS0: + return QString("Mode parameter 0"); + break; + case MODE_PARAMS1: + return QString("Mode parameter 1"); + break; + case MODE_PARAMS2: + return QString("Mode parameter 2"); + break; + case MODE_PARAMS3: + return QString("Mode parameter 3"); + break; + case CONDITION: + return QString("Condition"); + break; + case CONDITION_PARAMS0: + return QString("Condition parameter 0"); + break; + case CONDITION_PARAMS1: + return QString("Condition parameter 1"); + break; + case CONDITION_PARAMS2: + return QString("Condition parameter 2"); + break; + case CONDITION_PARAMS3: + return QString("Condition parameter 3"); + break; + case COMMAND: + return QString("Command"); + break; + case JUMPDESTINATION: + return QString("Jump Destination"); + break; + case ERRORDESTINATION: + return QString("Error Destination"); + break; + case LOCKED: + return QString("Locked"); + break; + default: + return QString(); + break; + } + } + } + return QVariant(); +} +bool flightDataModel::setData(const QModelIndex &index, const QVariant &value, int role) +{ + if (role == Qt::EditRole) + { + //save value from editor to member m_gridData + int columnIndex=index.column(); + int rowIndex=index.row(); + if(rowIndex>dataStorage.length()-1) + return false; + pathPlanData * myRow=dataStorage.at(rowIndex); + setColumnByIndex(myRow,columnIndex,value); + emit dataChanged(index,index); + //for presentation purposes only: build and emit a joined string + } + return true; +} + +Qt::ItemFlags flightDataModel::flags(const QModelIndex & /*index*/) const + { + return Qt::ItemIsSelectable | Qt::ItemIsEditable | Qt::ItemIsEnabled ; +} + +bool flightDataModel::insertRows(int row, int count, const QModelIndex &/*parent*/) +{ + pathPlanData * data; + beginInsertRows(QModelIndex(),row,row+count-1); + for(int x=0; xlatPosition=0; + data->lngPosition=0; + data->disRelative=0; + data->beaRelative=0; + data->isRelative=0; + data->altitude=0; + data->velocity=0; + data->mode=0; + data->mode_params[0]=0; + data->mode_params[1]=0; + data->mode_params[2]=0; + data->mode_params[3]=0; + data->condition=0; + data->condition_params[0]=0; + data->condition_params[1]=0; + data->condition_params[2]=0; + data->condition_params[3]=0; + data->command=0; + data->jumpdestination=0; + data->errordestination=0; + data->locked=false; + dataStorage.insert(row,data); + } + endInsertRows(); +} + +bool flightDataModel::removeRows(int row, int count, const QModelIndex &/*parent*/) +{ + beginRemoveRows(QModelIndex(),row,row+count-1); + for(int x=0; xwpDescritption); + field.setAttribute("name","description"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->latPosition); + field.setAttribute("name","latitude"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->lngPosition); + field.setAttribute("name","longitude"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->disRelative); + field.setAttribute("name","distance_to_home"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->beaRelative); + field.setAttribute("name","bearing_from_home"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->isRelative); + field.setAttribute("name","is_relative_to_home"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->altitude); + field.setAttribute("name","altitude"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->velocity); + field.setAttribute("name","velocity"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->mode); + field.setAttribute("name","mode"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->mode_params[0]); + field.setAttribute("name","mode_param0"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->mode_params[1]); + field.setAttribute("name","mode_param1"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->mode_params[2]); + field.setAttribute("name","mode_param2"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->mode_params[3]); + field.setAttribute("name","mode_param3"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->condition); + field.setAttribute("name","condition"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->condition_params[0]); + field.setAttribute("name","condition_param0"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->condition_params[1]); + field.setAttribute("name","condition_param1"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->condition_params[2]); + field.setAttribute("name","condition_param2"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->condition_params[3]); + field.setAttribute("name","condition_param3"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->command); + field.setAttribute("name","command"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->jumpdestination); + field.setAttribute("name","jumpdestination"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->errordestination); + field.setAttribute("name","errordestination"); + waypoint.appendChild(field); + + field=doc.createElement("field"); + field.setAttribute("value",obj->locked); + field.setAttribute("name","is_locked"); + waypoint.appendChild(field); + + } + file.write(doc.toString().toAscii()); + file.close(); + return true; +} +void flightDataModel::readFromFile(QString fileName) +{ + //TODO warning message + removeRows(0,rowCount()); + QFile file(fileName); + QDomDocument doc("PathPlan"); + qDebug()<<"FILE OPEN"<altitude=field.attribute("value").toDouble(); + else if(field.attribute("name")=="description") + data->wpDescritption=field.attribute("value"); + else if(field.attribute("name")=="latitude") + data->latPosition=field.attribute("value").toDouble(); + else if(field.attribute("name")=="longitude") + data->lngPosition=field.attribute("value").toDouble(); + else if(field.attribute("name")=="distance_to_home") + data->disRelative=field.attribute("value").toDouble(); + else if(field.attribute("name")=="bearing_from_home") + data->beaRelative=field.attribute("value").toDouble(); + else if(field.attribute("name")=="is_relative_to_home") + data->isRelative=field.attribute("value").toInt(); + else if(field.attribute("name")=="altitude") + data->altitude=field.attribute("value").toDouble(); + else if(field.attribute("name")=="velocity") + data->velocity=field.attribute("value").toDouble(); + else if(field.attribute("name")=="mode") + data->mode=field.attribute("value").toInt(); + else if(field.attribute("name")=="mode_param0") + data->mode_params[0]=field.attribute("value").toDouble(); + else if(field.attribute("name")=="mode_param1") + data->mode_params[1]=field.attribute("value").toDouble(); + else if(field.attribute("name")=="mode_param2") + data->mode_params[2]=field.attribute("value").toDouble(); + else if(field.attribute("name")=="mode_param3") + data->mode_params[3]=field.attribute("value").toDouble(); + else if(field.attribute("name")=="condition") + data->condition=field.attribute("value").toDouble(); + else if(field.attribute("name")=="condition_param0") + data->condition_params[0]=field.attribute("value").toFloat(); + else if(field.attribute("name")=="condition_param1") + data->condition_params[1]=field.attribute("value").toFloat(); + else if(field.attribute("name")=="condition_param2") + data->condition_params[2]=field.attribute("value").toFloat(); + else if(field.attribute("name")=="condition_param3") + data->condition_params[3]=field.attribute("value").toFloat(); + else if(field.attribute("name")=="command") + data->command=field.attribute("value").toInt(); + else if(field.attribute("name")=="jumpdestination") + data->jumpdestination=field.attribute("value").toInt(); + else if(field.attribute("name")=="errordestination") + data->errordestination=field.attribute("value").toInt(); + else if(field.attribute("name")=="is_locked") + data->locked=field.attribute("value").toInt(); + + } + fieldNode=fieldNode.nextSibling(); + qDebug()<<"field node is null"< +#include "opmapcontrol/opmapcontrol.h" + +struct pathPlanData +{ + QString wpDescritption; + double latPosition; + double lngPosition; + double disRelative; + double beaRelative; + bool isRelative; + double altitude; + float velocity; + int mode; + float mode_params[4]; + int condition; + float condition_params[4]; + int command; + int jumpdestination; + int errordestination; + bool locked; +}; + +class flightDataModel:public QAbstractTableModel +{ +public: + enum pathPlanDataEnum + { + WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, + VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, + CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, + COMMAND,JUMPDESTINATION,ERRORDESTINATION,LOCKED + }; + flightDataModel(QObject *parent); + int rowCount(const QModelIndex &parent = QModelIndex()) const ; + int columnCount(const QModelIndex &parent = QModelIndex()) const; + QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; + QVariant headerData(int section, Qt::Orientation orientation, int role) const; + + bool setData(const QModelIndex & index, const QVariant & value, int role = Qt::EditRole); + Qt::ItemFlags flags(const QModelIndex & index) const ; + bool insertRows ( int row, int count, const QModelIndex & parent = QModelIndex() ); + bool removeRows ( int row, int count, const QModelIndex & parent = QModelIndex() ); + bool writeToFile(QString filename); + void readFromFile(QString fileName); +private: + QList dataStorage; + QVariant getColumnByIndex(const pathPlanData *row, const int index) const; + bool setColumnByIndex(pathPlanData *row, const int index, const QVariant value); +signals: + //void dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); + + + +}; + +#endif // FLIGHTDATAMODEL_H diff --git a/ground/openpilotgcs/src/plugins/opmap/images/Ekisho Deep Ocean HD1.png b/ground/openpilotgcs/src/plugins/opmap/images/Ekisho Deep Ocean HD1.png new file mode 100644 index 0000000000000000000000000000000000000000..54cd51b00dbe69cffab74894eb76d33058bfa589 GIT binary patch literal 3263 zcmV;w3_$aVP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2c$_vK~z|U zm6u&?T*Vc~e=~FM-M#Czy&sNaIk6pL0wz!>N?Wy&iV%J2OCMU*5>lTKlG_)=TS2r) zs6Y{wDugPf5`u^3<0V0*2nwnQ4@fBmLHLNA5GS??L5Us5*BHS!?|My2 zM>;xZ=FZ&npYwIk6|{|$Cr^Gqo9+9#wTx`8YP3!yV-g{m8?&<7I1jc~1$=>Pd&()zrfAL;;;ZXU?mCN@}PEP*##EBCcKr{io^Ugb?g~H$) zQ54=?DCC%#nZa|*07$8eLI~G393Mr|O_knE;Z`}D?V(ax!5D*5%GFvGyMj;%rznJQthMagwVS@a zG($r}xUP#3tx)-&BMd`6KK&UwGA$RR(krJA?Zq|>Pm<<_kXgb#<}j0>|kcR7!g3be7j&|0nm|cOP1tE>ml5 zh;>9d?Nce2iQ|YcjEJI;w4Wl5V}uafx?p_oEu236Ih9Hc$8lW8NeuuOWs(6=QA*`n zYgk&o{*9(S{pqJnpFM|;Bf>Bs2m*p&gCGdFzO>BozrXg4?vYY5eRdkHW0Z1S5StdT z)(kYFll5AyWx}nu7}+(9ww53WiK2wUFd~j4qA2Fz4}Z{=g6(p>zD^u#gb=Qj476v# z4#yF$F@|f`mI%WTDP`N?B>MCDJmceg$Ye6i&dyS;t|FD9uYZV%+i&CJk4_VY;kE!O zl?noZ)-jIbxFB}402pKYtwm{V7#|;J{?a9G85`R+t!8Fs>Fw>ISR7#d)^S!UD=aK6 z^Pl%W=(>IT*_jLHxn=L(MlCRoF*euc0#US9dd3(Yxc>nzUcN#Q1~|&;a)q^qa(RVP zsdCdA&`wGT!Z6^DiMt!IAzf>Ap#?x|Q?M4-7(+UhV%LrV+)OW?(5$c3Zc<#j6>go6 zjg2rcP~ggyYpstL;2I+fZ5E&)C2kUYmfoHW_3A2n_TNTd*5~~B3sfrAZ+&Bc;o%_; z9QZDkN|m?Yeiz4a8>wvp>q==708>*_uC??VV_ai4J0M3X&Y!zLKHtZ_eYcX&=a`;8 zOQ}?*R;v?+QCk~k@jREFo(w}nJGtkc?{MQriTB=npZWRABpOXMcfa?qo z5BCdUotc?0c;%Isc>3w*JM#DX^%9GV*GZ*3cJChIjyon892_8%$j!JIm2ZxTi3uKj@E9+@d`wxJPB~9K_1M*4PyI$7{Lv#qDUXTU z_Y!N3(VCXLPc8n; zA0Ok1$DiwPQ4nlkjGX(-rg*w zQpq|1nM}V3f(@$G3Z9q3^HM}{%-q~83kwU3j*K!mI7DAxuEPSp?^CT-$Ye6xa)6QD zBh3Hp2-Ru@b3>{@a?7FrXWZ2ru`EP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1GPy+K~z|U z?UvtbTV)u>KRI2JwriH1IdN7u8DiUXsUqT?BNW9uuiU>NbAq5Zq6~H+2!(>8h;!;D zc;m%zcOndQN!y9rItR+wmA1`kv$k1n(!`VVpYuF# za$fj<{l_a7RXF+1eIFSy<3v=w((3f3lN+z}1mL+TGo4DLE9YK*8&|A{>XY#U9DDb5 zzCBqE_1_f*006CNh!VC}440xn>qxed0kqaAB~eO*YNeLwUIU;(X^GI`07^-Smj5?8 zpfpnY2JE! z_)>t1l#dZbbpAY2Dv6K+Pq?8ah>bF>_%!ivA zM(+WdzXFXX!i|O0|9k|wSNl&9GfrS|005<_In_u2HKz(nlY4EjDb~7=#Qtkf9NsJUig~D z((2Lt`;EDFZC^Ko;&saVGp@e1XiXkGn8vEyq+DOY@g1Zhv>e~1VsB7$t0enOzWQdK z#ii18;Y0UqXI57LfTej^FtftAU8?7v96LhYuiy#~sha2OUZr)6WPFH+(pfI$ixi8u zrwbo@ceVeX007oCkvETc#@ec#dtx+0-K*jV7pe5NPp?#r#I7M8PG>0;EQ-sk(=%tf zhlc_HSo1P(W;|nk)y_RWnxW=y1rXiClkpUX_D(Q2Q^ZPxH^&^~ z&YGQ@7#pYV{RPq9_JKr-N6aig%r3HItxnB-=D!){9SH!y`cdW0jB9L`?Ob+bj4iK< z2AA@(nd>9&W^|8_qM?%s2|oA#;SQgdh)4f`R?L1mKMrqu6(IJ08&Bi2Ks?S z8%Wo%&SlX2i|!9hI?ei8PdM?s@#5ZLUaFM%^yiD}0w8H#MFijjF7P{02Wo&5?CYSq z0>lD<1TX*$2I0w|EA8zyg3mHAYyrps!V5y}pxidiwjF5gw+Hlf?8Ufywz{KKTgkTI eh!^&MY5f7RH%44Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w23|=-K~z|U z?UqYyTvr*#f9KwrJ8zF?Y{&IGHZ>tloVqQEl*%Z5gjb5XK&7lvcU2Kxp+;h1q)GwA z0--9vqEaOgC`3r02EA zzjMCd`OmrE9QgnEUms#S$>Hx^>Wu`d&&F z$mREDZ#DEZ@88|qOy1L+zN?rk zYFzbT+mwOjGMw`i^973oEjGLRnwig*_j{gqJO|%;r~|3*ygy_T4SyOqu$xC4EXGz8 zi$%TVska&d0qrr1Cz@<#bDHtLOyL#_PnUmk`1}JMkXjxKq|&s6;PSH1QcE$Yp;7e4#$is-HNoof;5MXeil|B2!W<tEAmV!bSeTdVg$gOXr5 z4o1se>s((4ApNuu7M`c7s{o@kzVEN)G(;U8G~@Kzg7QzHin5s5$V@qpdl~k)eT2wP+&2SHCpG+@%7u6M2C9d&>1)dA$S5 z&uG_88!Lpl=Rh5R5Q0b~LNFBJcQZvsCYSl~v&m{60#`T`a2UB(;nx!xZsqR785^|g zVwAtGC9enY<&4Vb4qBl!LK(C%7^N}B5R1hi5ayQ?d47K34od~eKvE)=#l&PMk>`eg6DH^y~7bGEo}g9wI% zWpFE!a@oiDYC}{il1fExsu^D)q$Xh*A{dGbH_-Xa+4|xe0IH`^N4>>a@+C=Y#3E)J zkQ(i)Z3R*jw+*cki+oAqEq;t!DSdZ?LmNE1Hacf@Jh@YOYOuNW5z=8B&r`UbMk$Ta z=AmH&jUkJ!#voc7ZcUEiF5i4dj~;vL;Q)Z{dH%Fny?q#Ab+k0MvLhZqU~oN+^fh`5 z5MioMv-XA{z3C7bn7cC0>eb1QJa_gR%uj7-8k+)eW7Lz~{qGj;WDcU~Zh54Q&PIo} zh9GgrA}9nHs;3nYb1Yh70d_Vy>}n0u))2&(n%VKcGe0$U#?vb=a{gEO%}PD^Z+_3P zV}UG_?la{=D9L;nU$rRZ|i*eRVIhG z^(eJ~AP@#(K!U!*&xyvKR})R0dpmpkX>0Ey6bjOmN&&Ev&EmQ~ON+Odzy2}#mH7#? za{U+F{9qI)07ak#xK!UNYv1i=0CrvRMj#C&fC!EKz1EKYr%kA70LzYwK)46Mc;z|J zMd4;9^quMRtX{hTRBDA+YmuwX6|mM+HUkhf2kyBL1)SR4u7y?0ySLudg{~EmfCrRo jFfQQN^liQ{|BK@vV;!;Jm4x)U00000NkvXXu0mjfF!YL2 literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/opmap/images/forward_alt.png b/ground/openpilotgcs/src/plugins/opmap/images/forward_alt.png new file mode 100644 index 0000000000000000000000000000000000000000..ddd2e4261c32d8aaccd9ca8f8e23037b0f63a9db GIT binary patch literal 2217 zcmV;a2v+xrP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1CB{VK~z|U z?UsFLRb?EQtBt1``9%~*F1pgOeYg{tRSaepOc;gaPoJr^Fiw<CU{wn9-L$m0*KWh6bkh6jhD^BxPG z?`u)UZsr#N)!XOn$Kkc9LVUh?AF4U*9w?B67oS{0$Hh+e9sd-~&|hlakvw#BfNc@y z>)Ioz#?Yk0En7#oQdqY3k9A4Ncs)g=G6o+ve!`W3zPeK%Tz_l4Uk1Q-7*i9Bs)9J5~Q`!+?qh(lLM3&EySnKr}0<^>2&&?)&}$a@qPiY;#JRn;Yd?{6|Z}836};h z03Zp8a3I3M$P)hQ&d|~MYm+I7SX+a6;@`Yts-an}d_{Ji+OUkyzBoRQpYrfL?)Kfs z=`)=S4kdTB9xylG$}blR;Mfk9Bk;>%?kQV@dd<(b@fLK`db#bOb>MdXf&p+GN{gZ_ zF7~a}7iLzo`fv3&Ql)XO;vtou00000NkvXXu0mjfMnW;) literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/opmap/images/new archive.png b/ground/openpilotgcs/src/plugins/opmap/images/new archive.png new file mode 100644 index 0000000000000000000000000000000000000000..326c2bb3a99292ef0426f4973b3f577f5c774e63 GIT binary patch literal 2670 zcmV-!3X%1RP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1ye~xK~z|U z?Uqf5l~owWf9Jh-#u>*M)5g#I%mPKM5F^AsP#4jnXk)fW3=6}GiX<}JxTr-&WMvad zR8R;ZEsXXqf`W*O2#Tmoo2)VIIx{+R?>WyoPmA+@-aC>TYtsvt^SSdMGi;E`Xrn&EtE|J^HV*+Wh>W4v#*f!=sPr=I00XN@CU9CtiJU(e=l| zB|uB2m#3aS%H$;p zsHz#-y=D)70w?LDS61Ho07+8ABnigE--WReOjlXOou}cy-_}J?G19KPcP#LBr(RuZO{(+e!DKIICi3?}RB4kiz^bepKAfzNR^(leA z)f*T)_xqzS?OgHAGlzdVlwq2U&kYO#yV^_f?6&0qy!hUUj=F8SZWDJczXy!TtYgmX zS)iJ`Kwg4?YP@g!d79%Ny@QxAfA3o-MgZ#Sb=S*}Z{^JR_c=gQ#uyp<4S*-^Uq(-T zAYYr?zmnYtKVa)EPgY2Ma_ki}c)S;acX;pc;_zY#V&l9xYKdT*&5wbbBLN9mQ6_B> z_NG%VwBmDDqG%}AtSBmhu`|CGO{{Roy$=`abLEA44RLZpQ+J<YWp624)ZRVv>YfW_MP9V=x$&Etyx@32m!|q8(+>>~PWms)z^@ z0%PS2q*+6};L>z=cO{r4L4(6tUr`@VL@ERn(l*ozcqCNZixPtsKDGQpHq70m^iH{CcLU>U^_cRi`6~s!caT>A=FjHJ8Z~vavk`tv& zprw$;GFvOq9JQ4ah*!jWtVjV`CXr$m_iY4H@Z5pSmlC+5_@J~}j-#K&4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1+hs)K~z|U z?Uq|?Tvru_zrD{~J!6k&e2X)-8^@(q!7eG(61Ea0DNP?*HHb(Nub@gG`h<9>6qF(h zs#f9!A(d9GRKY8XL{tz6k~YFLWq@7?xwTHy#EEC(*!68DGoG1q_JxN`tvTbFK-5Y+ zz>=19eyw%(|F5;rK6}Cc?SI|G-6TJHG%;-20^cw=2c$I#3%hEIoH0V?CHkb?P`^6y zZ2szJD&W9#oqLT6K0nl#oP1>b0X{!4Ml=+sJH7*e<>DM=x5&lpd0szvmg|da85!`7 zoczK1%%>7?c$(11PWOuwJGVdi#KZwc`yV18I}t*n%?8F+0FWYrBipdnpv*e63-9pT zw@>oUmE23+dgXh^rg86Dz@F#gJz*6)c4%sR?_*!uPdJc9>2*rpEM@O9Rh2`VJOGYN z5Duh?2Ja;n93>zVR8)@Nzjun`nF}+HSv>T|X;%MZ0sE$jhlATreeEkF6JH&l!jVx5 zm48sI{u9rvVXbOjjR+8wN#fxz(h+$OZOXiH_AmVUZP-2y ze=A_$baHn(rG9p3_aKf;uv*Gcbg!X|+nTt+wNX^{I<8tF==75AsW6*e-j#YVcH-LU za<-l?u%&#@K0h|Ba6}I)r88`Jxuz}u?xP7Ge(6NMAw%Km9LhMvLOU26zQ~Ow@e^QA zO97M5B*(kj_3qCNMk%?=6e{x=>un(i*uQ_jU$;KqB+EnTc_7Z{P?UE+aCc8WlN`_d zcB1NG*PgS)%J!q}{RL#Fjz@=d42{oY?!y&TMM#UZHq}yq zH5OL^*2VP~h*B*#xv9C0>9sYj@fX%8V6{{xMMQk|0+5u-w>er0K$+Qmfyr=4qKv>= zvl%+_^M`z?Kl*mYhky9Wq!0h~>YJO-LP(?*{9$QHOs0|&V9;W z4}a<-(AvM}jq!R5IuR6-#YKUU=6Cfm-!XIr$3MOaCAWklJ5WY`>SL&k#E~78+!D)+ zpbfuiDIoKLd#+dzr*rczf;JqHKxv7m*y37ipEt`TH@8HJ00AciSX@=+#zK}$?_XjmxAy9K$vk!8*xe1K5(okjAO^IL?&0C&ka#ND z+dejM&vyFyw-FA8NhEIn*7NyQs$P}Fg_~rr-C%9$*7?;r`|_o?_!CeBO27tC1vIev zKW-+#sUz4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w23bi&K~z|U z?Uq|?RaqIwe{1h^_UXCxT-s7v3IznQbP5a#2@NBYDMn_-@ZfEHHS;zZBTohrWBOnM z@yRGbO`K>(V{}Li^WZoM&P*8z#LVd%C2=AId-6KKLIs z5IgeGzF;75G@T6Zd3IAH&#Z|O4?3(*1_2nFmE@%1%6Nebx2DL>md;D1j^vN-KJ)Jx z=)LMCWbwqh*3_$C-qyqy+M*;qfg_-#EG1n{3%d{w2#keU-|~;K0`Fd$WPE(~XEUMj zA$mLgl^giZhfNKMx|2J%w(jfcYGzGDFzZ`x%o%RyESaKZPF7RvgU}igd?qf~Qtyxm z3dW0uzx3bd;r-Le$do&NsX_sTnC4 zD*DN7(-x*maL(6^7CZE(3YXXyXi0F^?%yY%Dz=bzXCWz^9?Dos-eE>B4&3I=UfxL*Mc zOymu&HMGZFL^@4iZste8a|`pFg#+*PQ(eLf?M*bL$QCsdIfYgRVID_7OE%{RiOc*G zIjsy6IYqXpNi?MqUTClP`l+sE4Fr@r=*DBDJxeAhkxC=XBe+_!u`tY6vgbJTS&h8A%fs|^ws4@khh!|w z8z(aeV`|(8J)NuPxi|k<l4UPa}YSTqycNx7RU3@N~4uV0IlVFY$*)V z)3J&J-Cv|35d}agMY=rA3zK(h+;fj{)lX90Hrjwz;CLR^s4dHOz$%#*!ol}7Xv3!B z5U;fPyx85%s#FXBDdl|r{$!r#dzR*`HdWWvMI6R}*7L)MHBpbB%8&hoR?DoZRIu7$wc*W65BS!pd;I>U z;;s&p*Dg|Nlu{_AIQ+pBZx3ps@dTddq4guq8Z%$VYJ)X~YHgWa-hfm$bZ!pEXoNOc zr5VXqIQHQrUws;JUfRjuV{ zjn2(srMj`K0j2$S<)c&DVZ6%1=Kokg_@5YaNbMDy4*a;1`_RFVi~h&z@rmcsZDCYL?CP<)Yr>WcIcKXZ#*QPCWBh`JV(!AQL# zpbRnB(j0ck6%~HwCY5sWd!N*E7xnK>--xqj=X&ky9gWSaN!PjfzNX?Ev^H2{p9&X9 zh8)%=gBW8Oy?TMl)bOuO-_hewHvpLSp7-qR-Teq>O;cktt6~8JmWpps(qNV`B5d_( z)>cO&GbRe|2DUj)RV9I&R)-nXHPV= zw7>eft=m|;wvD==g8+POQMDZqa0Q+#us~TFMn}iEK5&`oiQzX)F8vx;dsp-*b$}pH z2SkB58~48;lI^d>8`_>}+pw9I*0qE}K^jsi0H$YVs8l2qnNh|DZ<3oHyJDvYf5Gtk zeLx;407ale^{q0$cb78YE)Y)wX&?@SNp9ZYtlHddLk(RxZbSs?+5xOz8Ua%fmFyLB z|Jr$G?+gLun(%B5bG5Ms=5MK`42W6>9(ExDc(t)xgHy|UINvUSsfj4S2TC4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1&B#RK~z|U z?Ure5RYerXe{=7BTU&g$ubUKUtzZ$M#j-Ra3i`nCB;x*RZ*f96M+ZM2wu&=|GGdAOP|Fs%Ocaz6Jw*#dzl#S5b}V zdmF>bvGyx_V3*pvLEkpsxyH2udt8>7=iiC08yF#ztm4b(?`sHF{AU0{>hZJAyBSmx zRFd2a?!yf_@&5#1XG5?eT(IEEV9rEPHmDTgyh^k{EZ*Em&KU;?>P|dw=6xUsd;lAP zMQp}uL?5@DQGk7~64io*@ko9p$OI_YSAq$pSD^{9@{9sl26yCFK7b$r$^zwhl1YqE z4%w4yF53MD^T#r$NPp~l-FRL|8Api7=(qvOZ`g!kC{QxPT!9v(zw-dUe|FP9xKziK ztJTk3E6vwYz@qPxj-%2tWiu3;Q-MAiY}o zwH87NlixqPl|=jY88cSVGPnXS8_%0Fmp@QEXBk+Byxa-{L;whY76c5x%@_m&&yjL` zXAWS4w0uz8YZC!fsDy)?U!cFW>4};5cq^c%0oHvgzr1~ROFjX!I=gTR*vGtR(-TR1 zFz3q7s4ee4kO}W($bNA9y;}Bx+vf!noXFvC*VD6i)7pxAori|)fpq!tMQz>WMYZwR ziu!W^g<7?DQf!#WKAIl()pFQ~UKSFz3S*8H81Q31YvA}}Yb zaB4}wIt;14u>&NIGa=go0yWKbqd(b31(2>y7%_y@2FLfdW9DUp%cuaxh>a<2N$#|Z zp?eS5j(6rmCge^hnKO$+Ex&T?=XJj*M7?m`Xva^%X9{Ou&E)bG1iHWX?5sZ_*+Z5% zff1Qd@p;{e*fn(=|5pG?XiH;7F*w=|!5Em+NSRd}+P$BSA74Sa&YA_!$hGP5&2`DO zhqrxF+wnvA@w2NJb57Ys7{_-&_de)tBRXX+*3M1WfV*L+FEOOnK8S})OG{(><}AGq zx^`hlXVJE&jX!pL!SNH$)3?9ntm_=`c7ku0z5>;y=Mj2nv2lN%8ChL?=~9X(h0(1p zI_(m6Z+!W^h0obH`{UEX$Z&1|Aw#pSH_NMWa;s?D)5XzG8`yckT3`FV{b9ESz$JM9 z5RqXk0ok-4x8^11s~N?;JJuY0cggh9>=oxMT26lD?6h4rkixsFB%nmbL^=?D^EQ2P z^=0!m^t86{>%qi3wHxh?e+(difDfrN_!!7|65&4xPTqy~!l`<6^dEHS3CcW#{y*B&BUfQ|4bWZRM4#Vw dG6nyazW^NOpNLoWBzXV;002ovPDHLkV1m14Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2YN|FK~z|U z<(GMoR96+ofA_xLXYCngpdn!xFf4&Yf<%FU0R$bT#EPb3tkRT;V(c=JN~k1^P%Kt3 zB*5uZL>9wL0<$o~OwZE$>wfQE|LC5fr)P*uY59kz z>Quj1_nz~8_q*rb^BVr&P5i3?dnZyBi&JMf86&j39zZB!mQ;;~X8&F7T>P&Pcs4+t zLlE?ol`WsJ;8whqRg{je1p&5c()U3#tw#?NX}Qp7LFk?~LjMs0&x~fV(?PIi&fME4 zfAK4nPnnJ|93TWj2oMsa%>D{N>T(Bv`^^iS{`E_zge3IMR-XR12|PPiZuAGnth;%| zy;RPa1zHzGi!8V_5Yov0ifqb6M=M7*|B!G~)0Vs2)x%fAFs?T6^MHJ8%#`caEL`^} zMPsf3D}&B?-`PgmkG##Lqlf8w_at^-7^laB;r5`F4NBqk6;ZS3Gnn0-w=C$n;D05m z-~6W)_}N&war}(w>uz~qHPYn*WrJ9X_NE&Ugn)WFNLfqca8+UGeDiw=iRmN{*@SjPQ=iOC@LO7Cu0aJ!>8_9 zftJQodkeOG2!Wjy)CHzZTkfBD9okHyQc2p69pdQAuk5yBYW?@(bQFUBw2WFq8*eQ5 z#@BHByjYPQto|^`mS*;E+JJev9Tn@xTUyHWMYqyDiZxdypd19JEn0|5Wx>txWe)xF zSE#fKeLqH5Avl2W%7KbLN7> z*qE=vAc1Y*b+}y1{o}@=l5tcjN#nlPh$Rwh@9W_YBY|(Plsl$=;>KXjO|wwR#GoJF z`vR9*I=5AIsrBbhHWF)ZMa82SXs(?+kv2bd!w3jJi^ta1pi@ayGETZT%$Z|2*T;2v#ANwviEF&bRqcG3LY%3ELro(rHjyMlY#5$()lJ%ymRvTj8gRj zb5oW&+;QO|wbQ2o;43b|((3wQ1hgTm90Kfk6yb6c?d}G_2Zi82uHbg3&%O22Us!@r z7IxACAkrP?!0#H!WK?K%FZ~1a4M9&Lmc&lRbATG9sTxMW(zvv3VaFqgjF(g_j%BHS z@@%u88*n;aT=b=7_{z#rW(sX4NF|cI_1gwa%f7q5m&5rnwx+`2G*HPz7AKX&R@lQ8 z(5k2V%wHMRb{gsSl1dtAWCbW7Tck-TgR`d8;O)9VqU9_ql^~Od(a_XGJgwH&hk340 zF)gVje3{7p*8u2DX_UBfoCk~0vN#vXWc!VsN>c6=Sg5%J0|u z;y`8beK(A&z>deznKU|W(%9NVOMg1Fp>Oyd53tV9GM^!qR=UJsBfXT=NTpvNroe_? zF2*cDjNQ|P-5aL4t(()G@!cM-RD7XHO>jo3K7plpyqeOwX_IXH^Jz1d~hUZM8lPeO+X7^TKI35muN|hc@&uq)-QJ zeW~19<73%q_m$P3i)zwB*WbaFA{^2f4yI_lQRpSr9y#8Z8>w;$oOwMnVM9Z=B4z8l z9_!r;d56mtXgY7nE!O1?&**=z^25UqG0JI`>vQN!lGD;!~nzg0jP*@RD zy8iJ9y9;9O3c6cNK4;qCcML7a zt657*)6lDFONkxZV`}Y@6gJr-FS)X4kq=A`*adij;+z)&UN;oq=8<2$)~UZ9a0>!% zsB{X73~)>6$v{SHI?U|$bY%3ArVRTISR5xSdjg07(cH61_9$w>(AB#EA5fC>0TOP& z=>pF@r@U#Lp=K6KCb=b*4n#>@=?|44aoLuQe@v+ZZO{#5$hPtX5YK`4=blZnM^Wbs zIv|mew-t`Ocgav0^VNgwX;V2Lc((IAlLH-iFZh@9KeE3A7jAss==MnK00000NkvXX Hu0mjfev>p| literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/opmap/images/unarchive.png b/ground/openpilotgcs/src/plugins/opmap/images/unarchive.png new file mode 100644 index 0000000000000000000000000000000000000000..e74f0a31c5b9984b2bf49ca57a78ce586844ed8c GIT binary patch literal 2996 zcmV;l3rqBgP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w2AN4jK~z|U z?Ur4PRaX_qe`}w6&pDT2fB`B5C=?=6QKVu&f=IE@glKEpq(O~}ni|pAm#S%E(wOjM zv^Fuu6hCUx2l`-(n%KlvV-rYhV^e7~miR#gTC{~37-j}$=H9cvmJjFLbMKu2eQET? zo$Tzr_POW&|Lea#_JRM8|M8Hy2jBhdnvLng{2>zac@cw{gzjpL0Wk=|@(ni+ym#^R zaTEoO#2C>SQ0=YW+aI~H*B<=J5!(IlHTn%zl|x_M^0nn_w%osL&5ei{j7ci+1Tm&0 zBZleAqe#VHQQo<8e+j6O7z0|7h!ug+Gk-WRmZTm|KG2Vu^c%}B9QpR}($x=a+ z`QN-U@yfgqJo<$j52RV^hkNe*9BIA)k*@S52;ESK0TC`-ngEfmbX>P|1XODks6!A@ zE%y@_-sI>rPv9l4eE7#_Mr#5G_mO79Yl~(g7}LNsnj}fHTpKA#Whafa4#}Y?w^xiVQMS{?6R z?2!Z!LBudRI@x<$Va19iJ@0GJd){j-&$ETY{OqxZnH(Eicksx>**XbTVPLe9_K4ig(3Q@D9~o4<&(eD1su4kmA<}WP z-1hD*ELvrF=G1dI=P3$Hrzj{2OJN<(dAxHt?{UuIyu&+Rp8J6J9`8LdDxG%0;?~G? zP2j??dvN3S&A6cpj9)ni5sWqvO{xU-bcz{1eA^x9;x@l}{dtO_z!nx;Sc;;+*#c`V z&K5Z9aMqT#vp8!@Qq~c?Cq!VP3c&|HW4^WRy_-MTST@br)Hzfm&1M6GVALQ%ki-yt z#1^yc-*X?2KX-(S$$4%bxv8#UTNEfdFAUnfoHT-JsYHxiu5!R^ddG%O?7sc|lZ%qY zYt#Gaus6PoE-haKV|`US@9{qN2>kX*zH#8rC6A>GvdO#lewxF-f0C9CGv!kf z46y^6CFGK^ckxa@%K8_<7Dca(qNsurt4pazrnE~!!TGB_>RxT0)66?orOP%BYN%{<`lGapI?F833d@iEOX1nbE)BTR$XCK!Xo)5$wzp@}PO zpXYPG=Cn_VzMP;7UJ?vGV6BJFlpP3x4~h?ghBomtpe{!Z6fq#3HqFq$Mpw6AWDbD} zyjGyAOCPwRgs2pS!5cTsS<)GjZOS)L_P0}=p8qzMSBN{ov6Hwp~07&N+^R;*stEyEqaKN~=Peu~*MZ%!ON z^vEN3ARtDl0tsR;Myk42i2TQ){R~v+J->9t9|aZz;{v2W4h&Um0wigQ5g`_eNr!;~ z!J^ipm0L<#3QC4hFc(P%ep8MJIG_M#fzCC(IC$`&QAGx)ifa88A}F%&X_9?Ulc4kJ q@~s&<=a0K~Nk)5Q{_Eo{0{s`p`N%@=pjO-f00004Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1BFRMK~z|U z?Uqe%8&wpBpBcy4vD46o6aq;Nr7B}tvoeEDnUez3?mbx9nL6{ljskzS3?%)R$K_q}IE z1OLY!WAqz5dzrtd$%#+9-m_OaZ-)}T_1yK+ua6ZVG0~kp6*~6$XBXcmm!Es1BUHPAA;F*GVrb&pV0pgkN>??ht^p#`^#eHnK zjyB2+hR-l_f9XPdwCvB_Ed8`E0P$;G*@3=L`pR$$sTUElfYJ)7EHq^XUph-}F&_&= zEB@S+I|$bR@oQb#f!y0q3?4trTz)y$9xeKFQ{{#bt^nen zbY;WO^rkNlk6@|!n&P@fn-Ef$cr6@dF8_DTf4bzKy|p_;Lx9A`o$3B(`!esOhN;MT zEKxuziBf7u327m8iSywI^UJF--|02~>@BM<#I68|4?EIFpF5HrOC~9cdsM^*Qp+vd z>!}KHE*xPYzZMIeDg<*sSAJ{?An`#*`bbZ2c5Ea`N#3PmZ=hThe*{7mcr_g1ucg(Y z;E7@|cY8a;jsQdBzT+?S^nE*i>1{lwz%+cA<`dY$!jfgAQoG7yv=i_h#_xR!ug6d9 ztvE6vnoq3#A70&EMVv8A9Q?1n>a zDL`pg%Qgidq;%zgkh1jvT4@&6?l80Td&99_kBM%%16m`L#*&Q}7D|I|A;9P;p1cNI zNG#z3KKQe!o40fYptT-9&x2&4jAx&TnL_6T6J35C?yZhK%qnoz1u zdmDw?9|u5c$KD1Z)jsurQX1*PTBY~)8dksG9!KV#KRNJnRMY?T3Eccd9XmV#`Zs`1 zKmx+KDnL7Wq*!fk0A8RSH~>5ebe1ta*c}0K!$9H@ItOKjS8c+o68ju|U zOa~y~6hG+fBnbGNXKg%m$Z!@@H9NI|3Q%$iuQ)0I)@}f`5T;Ye>&WBe)o0al)u=*L iC3$GS#r9+PZ^S=URwa2q4r*!u0000)),this,SLOT(on_selectedWPChanged(QList))); + connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(on_WPValuesChanged(WayPointItem*))); +} + +void modelMapProxy::on_WPDeleted(int wp_numberint,WayPointItem * wp) +{ +} + +void modelMapProxy::on_WPInserted(int wp_number, WayPointItem * wp) +{ + +} + +void modelMapProxy::on_WPValuesChanged(WayPointItem * wp) +{ + QModelIndex index; + index=model->index(wp->Number(),flightDataModel::LATPOSITION); + if(!index.isValid()) + return; + model->setData(index,wp->Coord().Lat(),Qt::EditRole); + index=model->index(wp->Number(),flightDataModel::LNGPOSITION); + model->setData(index,wp->Coord().Lng(),Qt::EditRole); + index=model->index(wp->Number(),flightDataModel::DISRELATIVE); + model->setData(index,wp->getRelativeCoord().distance,Qt::EditRole); + index=model->index(wp->Number(),flightDataModel::BEARELATIVE); + model->setData(index,wp->getRelativeCoord().bearingToDegrees(),Qt::EditRole); +} + +void modelMapProxy::on_currentRowChanged(QModelIndex current, QModelIndex previous) +{ + QList list; + WayPointItem * wp=findWayPointNumber(current.row()); + if(!wp) + return; + list.append(wp); + myMap->setSelectedWP(list); +} + +void modelMapProxy::on_selectedWPChanged(QList list) +{ + selection->clearSelection(); + foreach(WayPointItem * wp,list) + { + QModelIndex index=model->index(wp->Number(),0); + selection->setCurrentIndex(index,QItemSelectionModel::Select | QItemSelectionModel::Rows); + } +} +/* +typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, + MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, + MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; +typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, + ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, + ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; +typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT=0, COMMAND_ONNOTCONDITIONNEXTWAYPOINT=1, + COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, + COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; +*/ +void modelMapProxy::refreshOverlays() +{ + /* + QMutexLocker locker(&wplistmutex); + myMap->deleteAllOverlays(); + foreach(WayPointItem * wp,*waypoints) + { + customData data=wp->data(0).value(); + + switch(data.condition) + { + + } + + switch(data.mode) + { + case PathAction::MODE_FLYENDPOINT: + case PathAction::MODE_FLYVECTOR: + case PathAction::MODE_DRIVEENDPOINT: + case PathAction::MODE_DRIVEVECTOR: + if(wp->Number()==0) + myMap->WPLineCreate((HomeItem*)myMap->Home,wp); + else + myMap->WPLineCreate(findWayPointNumber(wp->Number()-1),wp); + break; + case PathAction::MODE_FLYCIRCLERIGHT: + case PathAction::MODE_DRIVECIRCLERIGHT: + if(wp->Number()==0) + myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,true); + myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,true); + break; + case PathAction::MODE_FLYCIRCLELEFT: + case PathAction::MODE_DRIVECIRCLELEFT: + if(wp->Number()==0) + myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,false); + myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,false); + break; + default: + break; + + } + } + */ +} + +WayPointItem * modelMapProxy::findWayPointNumber(int number) +{ + if(number<0) + return NULL; + return myMap->WPFind(number); +} +/* +WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, + VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, + CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, + COMMAND,JUMPDESTINATION,ERRORDESTINATION +*/ + + +void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int last) +{ + qDebug()<<"modelMapProxy::on_rowsRemoved"<<"first"<first-1;x--) + { + myMap->WPDelete(x); + } +} + +void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight) +{ + WayPointItem * item=findWayPointNumber(topLeft.row()); + if(!item) + return; + internals::PointLatLng latlng; + int x=topLeft.row(); + distBearing distBearing; + double altitude; + bool relative; + QModelIndex index; + QString desc; + switch(topLeft.column()) + { + case flightDataModel::WPDESCRITPTION: + index=model->index(x,flightDataModel::WPDESCRITPTION); + desc=index.data(Qt::DisplayRole).toString(); + item->SetDescription(desc); + break; + case flightDataModel::LATPOSITION: + latlng=item->Coord(); + index=model->index(x,flightDataModel::LATPOSITION); + latlng.SetLat(index.data(Qt::DisplayRole).toDouble()); + item->SetCoord(latlng); + break; + case flightDataModel::LNGPOSITION: + latlng=item->Coord(); + index=model->index(x,flightDataModel::LNGPOSITION); + latlng.SetLng(index.data(Qt::DisplayRole).toDouble()); + item->SetCoord(latlng); + break; + case flightDataModel::BEARELATIVE: + distBearing=item->getRelativeCoord(); + index=model->index(x,flightDataModel::BEARELATIVE); + distBearing.setBearingFromDegrees(index.data(Qt::DisplayRole).toDouble()); + break; + case flightDataModel::DISRELATIVE: + distBearing=item->getRelativeCoord(); + index=model->index(x,flightDataModel::DISRELATIVE); + distBearing.distance=index.data(Qt::DisplayRole).toDouble(); + break; + + case flightDataModel::ISRELATIVE: + index=model->index(x,flightDataModel::ISRELATIVE); + relative=index.data(Qt::DisplayRole).toBool(); + if(relative) + item->setWPType(mapcontrol::WayPointItem::relative); + break; + case flightDataModel::ALTITUDE: + index=model->index(x,flightDataModel::ALTITUDE); + altitude=index.data(Qt::DisplayRole).toDouble(); + item->SetAltitude(altitude); + break; + case flightDataModel::LOCKED: + index=model->index(x,flightDataModel::LOCKED); + item->setFlag(QGraphicsItem::ItemIsMovable,!index.data(Qt::DisplayRole).toBool()); + break; + } +} + +void modelMapProxy::on_rowsInserted(const QModelIndex &parent, int first, int last) +{ + Q_UNUSED(parent); + for(int x=first;xindex(x,flightDataModel::WPDESCRITPTION); + QString desc=index.data(Qt::DisplayRole).toString(); + index=model->index(x,flightDataModel::LATPOSITION); + latlng.SetLat(index.data(Qt::DisplayRole).toDouble()); + index=model->index(x,flightDataModel::LNGPOSITION); + latlng.SetLng(index.data(Qt::DisplayRole).toDouble()); + index=model->index(x,flightDataModel::DISRELATIVE); + distBearing.distance=index.data(Qt::DisplayRole).toDouble(); + index=model->index(x,flightDataModel::BEARELATIVE); + distBearing.setBearingFromDegrees(index.data(Qt::DisplayRole).toDouble()); + index=model->index(x,flightDataModel::ISRELATIVE); + relative=index.data(Qt::DisplayRole).toBool(); + index=model->index(x,flightDataModel::ALTITUDE); + altitude=index.data(Qt::DisplayRole).toDouble(); + item=myMap->WPInsert(latlng,altitude,desc,x); + item->setRelativeCoord(distBearing); + if(relative) + item->setWPType(mapcontrol::WayPointItem::relative); + } +} +void modelMapProxy::deleteWayPoint(int number) +{ + model->removeRow(number,QModelIndex()); +} + +void modelMapProxy::createWayPoint(internals::PointLatLng coord) +{ + model->insertRow(model->rowCount(),QModelIndex()); + QModelIndex index=model->index(model->rowCount()-1,flightDataModel::LATPOSITION,QModelIndex()); + model->setData(index,coord.Lat(),Qt::EditRole); + index=model->index(model->rowCount()-1,flightDataModel::LNGPOSITION,QModelIndex()); + model->setData(index,coord.Lng(),Qt::EditRole); +} +void modelMapProxy::deleteAll() +{ + model->removeRows(0,model->rowCount(),QModelIndex()); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h new file mode 100644 index 000000000..ec7e1e434 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h @@ -0,0 +1,41 @@ +#ifndef MODELMAPPROXY_H +#define MODELMAPPROXY_H +#include +#include "opmapcontrol/opmapcontrol.h" +#include "pathaction.h" +#include "waypoint.h" +#include "QMutexLocker" +#include "QPointer" +#include "flightdatamodel.h" +#include + + + +using namespace mapcontrol; +class modelMapProxy:public QObject +{ + Q_OBJECT +public: + explicit modelMapProxy(QObject *parent,OPMapWidget * map,flightDataModel * model,QItemSelectionModel * selectionModel); + WayPointItem *findWayPointNumber(int number); + void createWayPoint(internals::PointLatLng coord); + void deleteWayPoint(int number); + void deleteAll(); +private slots: + void on_dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); + void on_rowsInserted ( const QModelIndex & parent, int first, int last ); + void on_rowsRemoved ( const QModelIndex & parent, int first, int last ); + + void on_WPDeleted(int wp_numberint, WayPointItem *); + void on_WPInserted(int,WayPointItem*); + void on_WPValuesChanged(WayPointItem *wp); + void on_currentRowChanged(QModelIndex,QModelIndex); + void on_selectedWPChanged(QList); +private: + OPMapWidget * myMap; + flightDataModel * model; + void refreshOverlays(); + QItemSelectionModel * selection; +}; + +#endif // MODELMAPPROXY_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index af12afa25..c571c3ca3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -1,4 +1,4 @@ -QT += webkit network +QT += xml TEMPLATE = lib TARGET = OPMapGadget include(../../openpilotgcsplugin.pri) @@ -15,12 +15,13 @@ HEADERS += opmapplugin.h \ opmapgadgetconfiguration.h \ opmapgadget.h \ opmapgadgetwidget.h \ - opmap_waypointeditor_dialog.h \ opmap_edit_waypoint_dialog.h \ opmap_zoom_slider_widget.h \ opmap_statusbar_widget.h \ - opmap_overlay_widget.h \ - pathplanmanager.h + flightdatamodel.h \ + modelmapproxy.h \ + widgetdelegates.h \ + pathplanner.h SOURCES += opmapplugin.cpp \ opmapgadgetwidget.cpp \ @@ -28,22 +29,22 @@ SOURCES += opmapplugin.cpp \ opmapgadgetfactory.cpp \ opmapgadgetconfiguration.cpp \ opmapgadget.cpp \ - opmap_waypointeditor_dialog.cpp \ opmap_edit_waypoint_dialog.cpp \ opmap_zoom_slider_widget.cpp \ opmap_statusbar_widget.cpp \ - opmap_overlay_widget.cpp \ - pathplanmanager.cpp + flightdatamodel.cpp \ + modelmapproxy.cpp \ + widgetdelegates.cpp \ + pathplanner.cpp OTHER_FILES += OPMapGadget.pluginspec FORMS += opmapgadgetoptionspage.ui \ opmap_widget.ui \ - opmap_waypointeditor_dialog.ui \ opmap_edit_waypoint_dialog.ui \ opmap_zoom_slider_widget.ui \ opmap_statusbar_widget.ui \ opmap_overlay_widget.ui \ - pathplanmanager.ui + pathplanner.ui RESOURCES += opmap.qrc diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.qrc b/ground/openpilotgcs/src/plugins/opmap/opmap.qrc index eae9fc9cd..99ff510f5 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.qrc +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.qrc @@ -25,5 +25,15 @@ images/home_wp.png images/move_to_wp.png images/center_wp.png + images/Ekisho Deep Ocean HD1.png + images/forward button white.png + images/new archive.png + images/rewind button white.png + images/stopb.png + images/unarchive.png + images/up_alt.png + images/plus3.png + images/forward_alt.png + images/star.png diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 9d1761c5e..3182e2cd8 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -28,48 +28,66 @@ #include "opmap_edit_waypoint_dialog.h" #include "ui_opmap_edit_waypoint_dialog.h" #include "opmapcontrol/opmapcontrol.h" +#include "widgetdelegates.h" // ********************************************************************* -typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, - MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, - MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; -typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, - ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, - ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; - // constructor -opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent) : - QDialog(parent, Qt::Dialog), +opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstractItemModel * model,QItemSelectionModel * selection) : + QWidget(parent),model(model),itemSelection(selection), ui(new Ui::opmap_edit_waypoint_dialog) -{ +{ ui->setupUi(this); my_waypoint = NULL; - connect(ui->rbRelative,SIGNAL(toggled(bool)),this,SLOT(setupPositionWidgets(bool))); + connect(ui->checkBoxLocked,SIGNAL(toggled(bool)),this,SLOT(enableEditWidgets(bool))); connect(ui->cbMode,SIGNAL(currentIndexChanged(int)),this,SLOT(setupModeWidgets())); connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets())); - ui->cbMode->addItem("Fly Direct",MODE_FLYENDPOINT); - ui->cbMode->addItem("Fly Vector",MODE_FLYVECTOR); - ui->cbMode->addItem("Fly Circle Right",MODE_FLYCIRCLERIGHT); - ui->cbMode->addItem("Fly Circle Left",MODE_FLYCIRCLELEFT); - ui->cbMode->addItem("Drive Direct",MODE_DRIVEENDPOINT); - ui->cbMode->addItem("Drive Vector",MODE_DRIVEVECTOR); - ui->cbMode->addItem("Drive Circle Right",MODE_DRIVECIRCLELEFT); - ui->cbMode->addItem("Drive Circle Left",MODE_DRIVECIRCLERIGHT); + ComboBoxDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); + ComboBoxDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); + ComboBoxDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); - ui->cbMode->addItem("Fixed Attitude",MODE_FIXEDATTITUDE); - ui->cbMode->addItem("Set Accessory",MODE_SETACCESSORY); - ui->cbMode->addItem("Disarm Alarm",MODE_DISARMALARM); + // VELOCITY, - ui->cbCondition->addItem("None",ENDCONDITION_NONE); - ui->cbCondition->addItem("Timeout",ENDCONDITION_TIMEOUT); - ui->cbCondition->addItem("Distance to tgt",ENDCONDITION_DISTANCETOTARGET); - ui->cbCondition->addItem("Leg remaining",ENDCONDITION_LEGREMAINING); - ui->cbCondition->addItem("Above Altitude",ENDCONDITION_ABOVEALTITUDE); - ui->cbCondition->addItem("Pointing towards next",ENDCONDITION_POINTINGTOWARDSNEXT); - ui->cbCondition->addItem("Python script",ENDCONDITION_PYTHONSCRIPT); - ui->cbCondition->addItem("Immediate",ENDCONDITION_IMMEDIATE); + mapper = new QDataWidgetMapper(this); + mapper->setItemDelegate(new ComboBoxDelegate(this)); + connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(on_currentIndexChanged(int))); + mapper->setModel(model); + //mapper->addMapping(ui->spinBoxNumber, + mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED); + mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION); + mapper->addMapping(ui->doubleSpinBoxLongitude,flightDataModel::LNGPOSITION); + mapper->addMapping(ui->doubleSpinBoxAltitude,flightDataModel::ALTITUDE); + mapper->addMapping(ui->lineEditDescription,flightDataModel::WPDESCRITPTION); + mapper->addMapping(ui->checkBoxRelative,flightDataModel::ISRELATIVE); + mapper->addMapping(ui->doubleSpinBoxBearing,flightDataModel::BEARELATIVE); + mapper->addMapping(ui->doubleSpinBoxVelocity,flightDataModel::VELOCITY); + mapper->addMapping(ui->spinBoxDistance,flightDataModel::DISRELATIVE); + mapper->addMapping(ui->cbMode,flightDataModel::MODE); + mapper->addMapping(ui->dsb_modeParam1,flightDataModel::MODE_PARAMS0); + mapper->addMapping(ui->dsb_modeParam2,flightDataModel::MODE_PARAMS1); + mapper->addMapping(ui->dsb_modeParam3,flightDataModel::MODE_PARAMS2); + mapper->addMapping(ui->dsb_modeParam4,flightDataModel::MODE_PARAMS3); + + mapper->addMapping(ui->cbCondition,flightDataModel::CONDITION); + mapper->addMapping(ui->dsb_condParam1,flightDataModel::CONDITION_PARAMS0); + mapper->addMapping(ui->dsb_condParam2,flightDataModel::CONDITION_PARAMS1); + mapper->addMapping(ui->dsb_condParam3,flightDataModel::CONDITION_PARAMS2); + mapper->addMapping(ui->dsb_condParam4,flightDataModel::CONDITION_PARAMS0); + + mapper->addMapping(ui->cbCommand,flightDataModel::COMMAND); + mapper->addMapping(ui->sbJump,flightDataModel::JUMPDESTINATION); + mapper->addMapping(ui->sbError,flightDataModel::ERRORDESTINATION); + connect(itemSelection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(on_currentRowChanged(QModelIndex,QModelIndex))); +} +void opmap_edit_waypoint_dialog::on_currentIndexChanged(int index) +{ + ui->lbNumber->setText(QString::number(index)); + QModelIndex idx=mapper->model()->index(index,0); + if(index==itemSelection->currentIndex().row()) + return; + itemSelection->clear(); + itemSelection->setCurrentIndex(idx,QItemSelectionModel::Select | QItemSelectionModel::Rows); } // destrutor @@ -80,68 +98,36 @@ opmap_edit_waypoint_dialog::~opmap_edit_waypoint_dialog() // ********************************************************************* -void opmap_edit_waypoint_dialog::changeEvent(QEvent *e) -{ - QDialog::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} - void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() { - int res = saveSettings(); - if (res < 0) return; - - my_waypoint = NULL; close(); } void opmap_edit_waypoint_dialog::on_pushButtonApply_clicked() { - saveSettings(); + } void opmap_edit_waypoint_dialog::on_pushButtonRevert_clicked() { - loadFromWP(my_waypoint); -} -void opmap_edit_waypoint_dialog::setupPositionWidgets(bool isRelative) -{ - ui->lbLong->setVisible(!isRelative); - ui->lbDegLong->setVisible(!isRelative); - ui->doubleSpinBoxLongitude->setVisible(!isRelative); - ui->lbLat->setVisible(!isRelative); - ui->lbDegLat->setVisible(!isRelative); - ui->doubleSpinBoxLatitude->setVisible(!isRelative); - ui->lbDistance->setVisible(isRelative); - ui->lbDistanceMeters->setVisible(isRelative); - ui->lbBearing->setVisible(isRelative); - ui->lbBearingDeg->setVisible(isRelative); - ui->spinBoxDistance->setVisible(isRelative); - ui->doubleSpinBoxBearing->setVisible(isRelative); } void opmap_edit_waypoint_dialog::setupModeWidgets() { - ModeOptions mode=(ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + ComboBoxDelegate::ModeOptions mode=(ComboBoxDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); switch(mode) { - case MODE_FLYENDPOINT: - case MODE_FLYVECTOR: - case MODE_FLYCIRCLERIGHT: - case MODE_FLYCIRCLELEFT: - case MODE_DRIVEENDPOINT: - case MODE_DRIVEVECTOR: - case MODE_DRIVECIRCLELEFT: - case MODE_DRIVECIRCLERIGHT: - case MODE_DISARMALARM: + case ComboBoxDelegate::MODE_FLYENDPOINT: + case ComboBoxDelegate::MODE_FLYVECTOR: + case ComboBoxDelegate::MODE_FLYCIRCLERIGHT: + case ComboBoxDelegate::MODE_FLYCIRCLELEFT: + case ComboBoxDelegate::MODE_DRIVEENDPOINT: + case ComboBoxDelegate::MODE_DRIVEVECTOR: + case ComboBoxDelegate::MODE_DRIVECIRCLELEFT: + case ComboBoxDelegate::MODE_DRIVECIRCLERIGHT: + case ComboBoxDelegate::MODE_DISARMALARM: ui->modeParam1->setVisible(false); ui->modeParam2->setVisible(false); ui->modeParam3->setVisible(false); @@ -151,7 +137,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(false); ui->dsb_modeParam4->setVisible(false); break; - case MODE_FIXEDATTITUDE: + case ComboBoxDelegate::MODE_FIXEDATTITUDE: ui->modeParam1->setText("pitch"); ui->modeParam2->setText("roll"); ui->modeParam3->setText("yaw"); @@ -165,7 +151,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(true); ui->dsb_modeParam4->setVisible(true); break; - case MODE_SETACCESSORY: + case ComboBoxDelegate::MODE_SETACCESSORY: ui->modeParam1->setText("Acc.channel"); ui->modeParam2->setText("Value"); ui->modeParam1->setVisible(true); @@ -181,12 +167,12 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() } void opmap_edit_waypoint_dialog::setupConditionWidgets() { - EndConditionOptions mode=(EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + ComboBoxDelegate::EndConditionOptions mode=(ComboBoxDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); switch(mode) { - case ENDCONDITION_NONE: - case ENDCONDITION_IMMEDIATE: - case ENDCONDITION_PYTHONSCRIPT: + case ComboBoxDelegate::ENDCONDITION_NONE: + case ComboBoxDelegate::ENDCONDITION_IMMEDIATE: + case ComboBoxDelegate::ENDCONDITION_PYTHONSCRIPT: ui->condParam1->setVisible(false); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -196,7 +182,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam3->setVisible(false); ui->dsb_condParam4->setVisible(false); break; - case ENDCONDITION_TIMEOUT: + case ComboBoxDelegate::ENDCONDITION_TIMEOUT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -207,7 +193,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Timeout(ms)"); break; - case ENDCONDITION_DISTANCETOTARGET: + case ComboBoxDelegate::ENDCONDITION_DISTANCETOTARGET: ui->condParam1->setVisible(true); ui->condParam2->setVisible(true); ui->condParam3->setVisible(false); @@ -219,7 +205,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->condParam1->setText("Distance(m)"); ui->condParam2->setText("Flag(0=2D,1=3D)");//FIXME break; - case ENDCONDITION_LEGREMAINING: + case ComboBoxDelegate::ENDCONDITION_LEGREMAINING: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -230,7 +216,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); break; - case ENDCONDITION_ABOVEALTITUDE: + case ComboBoxDelegate::ENDCONDITION_ABOVEALTITUDE: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -241,7 +227,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Altitude in meters (negative)"); break; - case ENDCONDITION_POINTINGTOWARDSNEXT: + case ComboBoxDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -265,80 +251,57 @@ void opmap_edit_waypoint_dialog::on_pushButtonCancel_clicked() int opmap_edit_waypoint_dialog::saveSettings() { - int number = ui->spinBoxNumber->value(); - if (number < 0) - { - return -1; - } - customData data; - data.mode=ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); - data.mode_params[0]=ui->dsb_modeParam1->value(); - data.mode_params[1]=ui->dsb_modeParam2->value(); - data.mode_params[2]=ui->dsb_modeParam3->value(); - data.mode_params[3]=ui->dsb_modeParam4->value(); - data.condition=ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); - data.condition_params[0]=ui->dsb_condParam1->value(); - data.condition_params[1]=ui->dsb_condParam2->value(); - data.condition_params[2]=ui->dsb_condParam3->value(); - data.condition_params[3]=ui->dsb_condParam4->value(); - - QVariant var; - var.setValue(data); - my_waypoint->setData(0,var); - - my_waypoint->SetNumber(ui->spinBoxNumber->value()); - my_waypoint->SetCoord(internals::PointLatLng(ui->doubleSpinBoxLatitude->value(), ui->doubleSpinBoxLongitude->value())); - my_waypoint->SetAltitude(ui->doubleSpinBoxAltitude->value()); - my_waypoint->SetDescription(ui->lineEditDescription->displayText().simplified()); - my_waypoint->setFlag(QGraphicsItem::ItemIsMovable, !ui->checkBoxLocked->isChecked()); - if(ui->rbAbsolute->isChecked()) - my_waypoint->setWPType(mapcontrol::WayPointItem::absolute); - else - my_waypoint->setWPType(mapcontrol::WayPointItem::relative); - mapcontrol::distBearing pt; - pt.distance=ui->spinBoxDistance->value(); - pt.bearing=ui->doubleSpinBoxBearing->value()/180*M_PI; - my_waypoint->setRelativeCoord(pt); - return 0; // all ok } void opmap_edit_waypoint_dialog::loadFromWP(mapcontrol::WayPointItem *waypoint_item) { - customData data=waypoint_item->data(0).value(); - ui->spinBoxNumber->setValue(waypoint_item->Number()); - ui->doubleSpinBoxLatitude->setValue(waypoint_item->Coord().Lat()); - ui->doubleSpinBoxLongitude->setValue(waypoint_item->Coord().Lng()); - ui->doubleSpinBoxAltitude->setValue(waypoint_item->Altitude()); - ui->lineEditDescription->setText(waypoint_item->Description()); - if(waypoint_item->WPType()==mapcontrol::WayPointItem::absolute) - ui->rbAbsolute->setChecked(true); - else - ui->rbRelative->setChecked(true); - ui->doubleSpinBoxBearing->setValue(waypoint_item->getRelativeCoord().bearing*180/M_PI); - ui->spinBoxDistance->setValue(waypoint_item->getRelativeCoord().distance); - ui->cbMode->setCurrentIndex(ui->cbMode->findData(data.mode)); - ui->dsb_modeParam1->setValue(data.mode_params[0]); - ui->dsb_modeParam2->setValue(data.mode_params[1]); - ui->dsb_modeParam3->setValue(data.mode_params[2]); - ui->dsb_modeParam4->setValue(data.mode_params[3]); - - ui->cbCondition->setCurrentIndex(ui->cbCondition->findData(data.condition)); - ui->dsb_condParam1->setValue(data.condition_params[0]); - ui->dsb_condParam2->setValue(data.condition_params[1]); - ui->dsb_condParam3->setValue(data.condition_params[2]); - ui->dsb_condParam4->setValue(data.condition_params[3]); } void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) return; - - this->my_waypoint = waypoint_item; - loadFromWP(waypoint_item); - setupPositionWidgets(ui->rbRelative->isChecked()); show(); + mapper->setCurrentIndex(waypoint_item->Number()); } // ********************************************************************* + +void opmap_edit_waypoint_dialog::on_pushButton_clicked() +{ + mapper->toPrevious(); +} + +void opmap_edit_waypoint_dialog::on_pushButton_2_clicked() +{ + mapper->toNext(); +} + +void opmap_edit_waypoint_dialog::enableEditWidgets(bool value) +{ + QWidget * w; + foreach(QWidget * obj,this->findChildren()) + { + w=qobject_cast(obj); + if(w) + w->setEnabled(!value); + w=qobject_cast(obj); + if(w) + w->setEnabled(!value); + w=qobject_cast(obj); + if(w) + w->setEnabled(!value); + w=qobject_cast(obj); + if(w && w!=ui->checkBoxLocked) + w->setEnabled(!value); + w=qobject_cast(obj); + if(w) + w->setEnabled(!value); + } +} + +void opmap_edit_waypoint_dialog::on_currentRowChanged(QModelIndex current, QModelIndex previous) +{ + mapper->setCurrentIndex(current.row()); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 0270afa3d..6fa87e7ef 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -29,19 +29,19 @@ #define OPMAP_EDIT_WAYPOINT_DIALOG_H #include - +#include #include "opmapcontrol/opmapcontrol.h" - +#include "flightdatamodel.h" namespace Ui { class opmap_edit_waypoint_dialog; } using namespace mapcontrol; -class opmap_edit_waypoint_dialog : public QDialog +class opmap_edit_waypoint_dialog : public QWidget { Q_OBJECT public: - opmap_edit_waypoint_dialog(QWidget *parent = 0); + opmap_edit_waypoint_dialog(QWidget *parent,QAbstractItemModel * model,QItemSelectionModel * selection); ~opmap_edit_waypoint_dialog(); /** @@ -52,17 +52,18 @@ public: void editWaypoint(mapcontrol::WayPointItem *waypoint_item); void loadFromWP(mapcontrol::WayPointItem *waypoint_item); -protected: - void changeEvent(QEvent *e); private: Ui::opmap_edit_waypoint_dialog *ui; mapcontrol::WayPointItem * my_waypoint; int saveSettings(); - + QDataWidgetMapper *mapper; + QAbstractItemModel * model; + QItemSelectionModel * itemSelection; private slots: private slots: + void on_currentIndexChanged(int index); void setupModeWidgets(); void setupPositionWidgets(bool isRelative); void setupConditionWidgets(); @@ -70,6 +71,10 @@ private slots: void on_pushButtonRevert_clicked(); void on_pushButtonApply_clicked(); void on_pushButtonOK_clicked(); + void on_pushButton_clicked(); + void on_pushButton_2_clicked(); + void enableEditWidgets(bool); + void on_currentRowChanged(QModelIndex,QModelIndex); }; #endif // OPMAP_EDIT_WAYPOINT_DIALOG_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index f77fcc965..0ebc74f17 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -1,15 +1,18 @@ opmap_edit_waypoint_dialog - + + + false + - Qt::ApplicationModal + Qt::NonModal 0 0 - 571 + 606 375 @@ -26,612 +29,711 @@ :/core/images/openpilot_logo_128.png:/core/images/openpilot_logo_128.png - - true - + + + 0 + 0 + + - 2 + 0 Position - - - - 0 - 10 - 528 - 266 - - - - - - - - 0 - 0 - - - - Latitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - true - - - - 0 - 0 - - - - Longitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Altitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - meters - - - - - - - - 0 - 0 - - - - Description - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - 200 - - - - - - - - 0 - 0 - - - - 7 - - - -90.000000000000000 - - - 90.000000000000000 - - - - - - - 7 - - - -180.000000000000000 - - - 180.000000000000000 - - - - - - - -5000.000000000000000 - - - 5000.000000000000000 - - - - - - - degrees - - - - - - - degrees - - - - - - - - 0 - 0 - - - - Type - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Relative - - - - - - - Absolute - - - - - - - 999999999 - - - - - - - meters - - - - - - - degrees - - - - - - - Bearing - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 360.000000000000000 - - - - - - - - 0 - 0 - - - - Distance - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::LeftToRight - - - Locked - - - - - - - Number - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - + + + + + + + + 0 + 0 + + + + Latitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + true + + + + 0 + 0 + + + + Longitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Altitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + meters + + + + + + + + 0 + 0 + + + + Description + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + 0 + 0 + + + + 7 + + + -90.000000000000000 + + + 90.000000000000000 + + + + + + + 7 + + + -180.000000000000000 + + + 180.000000000000000 + + + + + + + -5000.000000000000000 + + + 5000.000000000000000 + + + + + + + degrees + + + + + + + degrees + + + + + + + + 0 + 0 + + + + Relative to Home + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999 + + + + + + + meters + + + + + + + degrees + + + + + + + Bearing + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 360.000000000000000 + + + + + + + + 0 + 0 + + + + Distance + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::LeftToRight + + + Locked + + + + + + + Number + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0 + + + + + + + + + + + + + + Velocity + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + Mode - - - - -1 - -1 - 511 - 281 - - - - - - - - 0 - 0 - - - - - 100 - 0 - - - - Qt::LeftToRight - - - Mode - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - 999999999.000000000000000 - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param1 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param2 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param3 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param4 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 999999999.000000000000000 - - - - - - - 999999999.000000000000000 - - - - - - - 999999999.000000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Qt::LeftToRight + + + Mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 999999999.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param4 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + End condition - - - - 0 - 0 - 551 - 291 - - - - - QLayout::SetDefaultConstraint - - - - - - 0 - 0 - - - - - 100 - 0 - - - - Qt::LeftToRight - - - Condition - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - 999999999.000000000000000 - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param1 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param2 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param3 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Qt::LeftToRight - - - param4 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - 999999999.000000000000000 - - - - - - - 999999999.000000000000000 - - - - - - - 999999999.000000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + + + + QLayout::SetDefaultConstraint + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Qt::LeftToRight + + + Condition + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 999999999.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param1 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param2 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param3 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + param4 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + 999999999.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + - Page + Command + + + + + QLayout::SetDefaultConstraint + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Qt::LeftToRight + + + Command + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + Jump Destination + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + Qt::LeftToRight + + + Error Destination + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + + + + Previous + + + + + + + Next + + + @@ -652,27 +754,6 @@ - - - - Apply - - - - - - - Revert - - - - - - - Cancel - - - diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp deleted file mode 100644 index ac056f36b..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/** - ****************************************************************************** - * - * @file opmap_overlay_widget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "opmap_overlay_widget.h" -#include "ui_opmap_overlay_widget.h" - -opmap_overlay_widget::opmap_overlay_widget(QWidget *parent) : - QWidget(parent), - ui(new Ui::opmap_overlay_widget) -{ - -} - -opmap_overlay_widget::~opmap_overlay_widget() -{ - delete ui; -} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.h b/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.h deleted file mode 100644 index e10525d3d..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_overlay_widget.h +++ /dev/null @@ -1,49 +0,0 @@ -/** - ****************************************************************************** - * - * @file opmap_overlay_widget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef OPMAP_OVERLAY_WIDGET_H -#define OPMAP_OVERLAY_WIDGET_H - -#include - -namespace Ui { - class opmap_overlay_widget; -} - -class opmap_overlay_widget : public QWidget -{ - Q_OBJECT - -public: - explicit opmap_overlay_widget(QWidget *parent = 0); - ~opmap_overlay_widget(); - -private: - Ui::opmap_overlay_widget *ui; -}; - -#endif // OPMAP_OVERLAY_WIDGET_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.cpp deleted file mode 100644 index 64ce36c23..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.cpp +++ /dev/null @@ -1,184 +0,0 @@ -/** - ****************************************************************************** - * - * @file opmap_waypointeditor_dialog.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include -#include - -#include "opmap_waypointeditor_dialog.h" -#include "ui_opmap_waypointeditor_dialog.h" - -#include "extensionsystem/pluginmanager.h" - -// *************************************************************** -// Waypoint object - -WaypointItem::WaypointItem(QString name, double latitude, double longitude, double height, int time, int hold) : - waypoint_name(name), - latitude_degress(latitude), - longitude_degress(longitude), - height_feet(height), - time_seconds(time), - hold_seconds(hold) -{ - setToolTip(waypoint_name); - setFlag(QGraphicsItem::ItemIsMovable, true); - setFlag(QGraphicsItem::ItemIsSelectable, true); - setFlag(QGraphicsItem::ItemSendsScenePositionChanges, true); - - pixmap.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); -} - -QRectF WaypointItem::boundingRect() const -{ -// return QRectF(-6, -10, 12, 20); - return QRectF(-pixmap.width() / 2, -pixmap.height(), pixmap.width(), pixmap.height()); -} -/* -QPainterPath WaypointItem::shape() const -{ - QPainterPath path; -// path.addEllipse(QPointF(0, 0), 6, 10); - path.addRect(pixmap.rect()); - return path; -} -*/ - void WaypointItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *, QWidget *) -{ -// painter->setPen(Qt::black); -// painter->setBrush(QColor(255, 0, 0, 128)); -// painter->drawEllipse(QPointF(0, 0), 6, 10); - - painter->drawPixmap(-pixmap.width() / 2, -pixmap.height(), pixmap); -} - -void WaypointItem::setPixmap(QPixmap pixmap) -{ - this->pixmap = pixmap.copy(pixmap.rect()); -} - -// *************************************************************** -// Scene object - -OurScene::OurScene(QObject *parent) : QGraphicsScene(parent) -{ - movingItem = 0; -} - -void OurScene::mousePressEvent(QGraphicsSceneMouseEvent *event) -{ - QPointF mousePos(event->buttonDownScenePos(Qt::LeftButton).x(), event->buttonDownScenePos(Qt::LeftButton).y()); - - movingItem = itemAt(mousePos.x(), mousePos.y()); - - if (movingItem != 0 && event->button() == Qt::LeftButton) - { - oldPos = movingItem->pos(); - } - - clearSelection(); - - QGraphicsScene::mousePressEvent(event); - } - - void OurScene::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) - { - if (movingItem != 0 && event->button() == Qt::LeftButton) - { - if (oldPos != movingItem->pos()) - emit itemMoved(qgraphicsitem_cast(movingItem), oldPos); - - movingItem = 0; - } - - QGraphicsScene::mouseReleaseEvent(event); - } - -// *************************************************************** -// main dialogue - -opmap_waypointeditor_dialog::opmap_waypointeditor_dialog(QWidget *parent) : - QDialog(parent), - ui(new Ui::opmap_waypointeditor_dialog) -{ - ui->setupUi(this); - setWindowFlags(Qt::Dialog); - - view = ui->graphicsViewWaypointHeightAndTimeline; - - scene = new OurScene(); - scene->setSceneRect(QRect(0, 0, 500, 500)); - view->setScene(scene); - - waypoint_pixmap1.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - waypoint_pixmap2.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - - undoStack = new QUndoStack(); - - connect(scene, SIGNAL(itemMoved(WaypointItem *, const QPointF &)), this, SLOT(itemMoved(WaypointItem *, const QPointF &))); - - // ***** - // test - - WaypointItem *waypoint1 = new WaypointItem(tr("Waypoint 1"), 0, 0, 10, 5, 10); - waypoint1->setPos(scene->width() / 2, scene->height() / 2); - scene->addItem(waypoint1); - - WaypointItem *waypoint2 = new WaypointItem(tr("Waypoint 2"), 0, 0, 50, 8, 5); - waypoint2->setPos(scene->width() / 2 + 30, scene->height() / 2); - scene->addItem(waypoint2); - - WaypointItem *waypoint3 = new WaypointItem(tr("Waypoint 3"), 0, 0, 100, 8, 5); - waypoint3->setPixmap(waypoint_pixmap2); - waypoint3->setPos(scene->width() / 2 + 60, scene->height() / 2); - scene->addItem(waypoint3); - - // ***** -} - -opmap_waypointeditor_dialog::~opmap_waypointeditor_dialog() -{ - delete ui; -} - -void opmap_waypointeditor_dialog::changeEvent(QEvent *e) -{ - QDialog::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} - -void opmap_waypointeditor_dialog::itemMoved(WaypointItem *movedItem, const QPointF &oldPosition) -{ -// undoStack->push(new MoveCommand(movedItem, oldPosition)); -} - -// *************************************************************** diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.h deleted file mode 100644 index fd1ae72ea..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.h +++ /dev/null @@ -1,130 +0,0 @@ -/** - ****************************************************************************** - * - * @file opmap_waypointeditor_dialog.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef OPMAP_WAYPOINTEDITOR_DIALOG_H -#define OPMAP_WAYPOINTEDITOR_DIALOG_H - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "uavobjectmanager.h" -#include "positionactual.h" - -namespace Ui { - class opmap_waypointeditor_dialog; -} - -// *************************************************************** -// Waypoint object - -class WaypointItem : public QObject, public QGraphicsItem -{ - Q_OBJECT - Q_INTERFACES(QGraphicsItem) - - public: - WaypointItem(QString name = "", double latitude = 0, double longitude = 0, double height_feet = 0, int time_seconds = 0, int hold_seconds = 0); - - void setPixmap(QPixmap pixmap); - - QString waypoint_name; - double latitude_degress; - double longitude_degress; - double height_feet; - int time_seconds; - int hold_seconds; - - QPixmap pixmap; - - protected: - QRectF boundingRect() const; -// QPainterPath shape() const; - void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); -// void timerEvent(QTimerEvent *event); - - private: - -}; - -// *************************************************************** - -class OurScene : public QGraphicsScene - { - Q_OBJECT - - public: - OurScene(QObject *parent = 0); - - signals: - void itemMoved(WaypointItem *movedItem, const QPointF &movedFromPosition); - - protected: - void mousePressEvent(QGraphicsSceneMouseEvent *event); - void mouseReleaseEvent(QGraphicsSceneMouseEvent *event); - - private: - QGraphicsItem *movingItem; - QPointF oldPos; - }; - -// *************************************************************** -// main dialog widget - -class opmap_waypointeditor_dialog : public QDialog -{ - Q_OBJECT -public: - opmap_waypointeditor_dialog(QWidget *parent = 0); - ~opmap_waypointeditor_dialog(); - - public slots: - void itemMoved(WaypointItem *movedDiagram, const QPointF &moveStartPosition); - -protected: - void changeEvent(QEvent *e); - -private: - QPixmap waypoint_pixmap1; - QPixmap waypoint_pixmap2; - - QGraphicsView *view; - QGraphicsScene *scene; - - QUndoStack *undoStack; - - Ui::opmap_waypointeditor_dialog *ui; -}; - -// *************************************************************** - -#endif // OPMAP_WAYPOINTEDITOR_DIALOG_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.ui deleted file mode 100644 index ea9b65189..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_waypointeditor_dialog.ui +++ /dev/null @@ -1,248 +0,0 @@ - - - opmap_waypointeditor_dialog - - - - 0 - 0 - 561 - 511 - - - - - 0 - 0 - - - - - 300 - 0 - - - - OpenPilot GCS Waypoint Editor - - - - :/core/images/openpilot_logo_128.png:/core/images/openpilot_logo_128.png - - - true - - - - - - - - QSplitter::handle { -/* image: url(images/splitter.png); */ - background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 80), stop:1 rgba(0, 0, 0, 80)); -} - -QSplitter::handle:horizontal { - height: 5px; -} - -QSplitter::handle:vertical { - width: 5px; -} - - - QFrame::NoFrame - - - Qt::Vertical - - - true - - - 5 - - - false - - - - - 0 - 130 - - - - Waypoints - - - true - - - - 0 - - - 0 - - - - - - 0 - 0 - - - - - 0 - 50 - - - - true - - - false - - - false - - - - Num - - - - - Locked - - - - - Latitude - - - - - Longitude - - - - - Altitude - - - - - Time - - - - - Hold Time - - - - - - - - - Height and Timeline - - - true - - - - 0 - - - 0 - - - - - - 0 - 0 - - - - - 0 - 50 - - - - background-color: rgb(191, 191, 191); - - - QFrame::Sunken - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - QPainter::Antialiasing|QPainter::HighQualityAntialiasing|QPainter::TextAntialiasing - - - - - - - - - - - Qt::Horizontal - - - QDialogButtonBox::Cancel|QDialogButtonBox::Ok - - - - - - - - - - - - - buttonBox - accepted() - opmap_waypointeditor_dialog - accept() - - - 248 - 254 - - - 157 - 274 - - - - - buttonBox - rejected() - opmap_waypointeditor_dialog - reject() - - - 316 - 260 - - - 286 - 274 - - - - - diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 4fd28242c..6d105905c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -48,7 +48,6 @@ #include "positionactual.h" #include "homelocation.h" -#include "pathplanmanager.h" #define allow_manual_home_location_move // ************************************************************************************* @@ -215,8 +214,15 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - pathPlanManager * plan=new pathPlanManager(new QWidget(),m_map); - plan->show(); + model=new flightDataModel(this); + table=new pathPlanner(); + selectionModel=new QItemSelectionModel(model); + proxy=new modelMapProxy(this,m_map,model,selectionModel); + table->setModel(model,selectionModel); + table->show(); + waypoint_edit_dialog=new opmap_edit_waypoint_dialog(NULL,model,selectionModel); + + /* distBearing db; db.distance=100; @@ -1684,12 +1690,9 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) m_map->UAV->SetTrailDistance(trail_distance); } -/** - * TODO: unused for v1.0 - **/ void OPMapGadgetWidget::onOpenWayPointEditorAct_triggered() { - waypoint_editor_dialog.show(); + //TODO } void OPMapGadgetWidget::onAddWayPointAct_triggeredFromContextMenu() { @@ -1708,8 +1711,8 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) if (m_map_mode != Normal_MapMode) return; - m_map->WPCreate(coord, 0, ""); - + // m_map->WPCreate(coord, 0, ""); + proxy->createWayPoint(coord); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); @@ -1734,7 +1737,7 @@ void OPMapGadgetWidget::onEditWayPointAct_triggered() if (!m_mouse_waypoint) return; - waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); + waypoint_edit_dialog->editWaypoint(m_mouse_waypoint); m_mouse_waypoint = NULL; } @@ -1775,8 +1778,7 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() if (!m_mouse_waypoint) return; - // delete the waypoint from the map - m_map->WPDelete(m_mouse_waypoint); + proxy->deleteWayPoint(m_mouse_waypoint->Number()); } void OPMapGadgetWidget::onClearWayPointsAct_triggered() @@ -1787,7 +1789,7 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() if (m_map_mode != Normal_MapMode) return; - m_map->WPDeleteAll(); + proxy->deleteAll(); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index a2df40978..afb392a2d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -30,6 +30,11 @@ // ****************************************************** + +#include "flightdatamodel.h" +#include "pathplanner.h" +#include "modelmapproxy.h" + #include #include #include @@ -39,11 +44,8 @@ #include #include -#include "opmap_edit_waypoint_dialog.h" -#include "opmap_waypointeditor_dialog.h" #include "opmapcontrol/opmapcontrol.h" -#include "opmap_overlay_widget.h" #include "opmap_zoom_slider_widget.h" #include "opmap_statusbar_widget.h" @@ -54,7 +56,8 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "objectpersistence.h" - +#include +#include "opmap_edit_waypoint_dialog.h" // ****************************************************** @@ -234,9 +237,8 @@ private: UAVObjectManager *obm; UAVObjectUtilManager *obum; - opmap_waypointeditor_dialog waypoint_editor_dialog; - opmap_edit_waypoint_dialog waypoint_edit_dialog; + opmap_edit_waypoint_dialog * waypoint_edit_dialog; QStandardItemModel wayPoint_treeView_model; @@ -329,6 +331,11 @@ private: QMenu contextMenu; internals::PointLatLng lastLatLngMouse; WayPointItem * magicWayPoint; + + flightDataModel * model; + pathPlanner * table; + modelMapProxy * proxy; + QItemSelectionModel * selectionModel; }; #endif /* OPMAP_GADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp deleted file mode 100644 index 00a1734a3..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.cpp +++ /dev/null @@ -1,126 +0,0 @@ -/** - ****************************************************************************** - * - * @file pathplanmanager.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "pathplanmanager.h" -#include "ui_pathplanmanager.h" - -pathPlanManager::pathPlanManager(QWidget *parent,OPMapWidget *map): - QDialog(parent, Qt::Dialog),myMap(map), - ui(new Ui::pathPlanManager) -{ - waypoints=new QList >(); - ui->setupUi(this); - connect(myMap,SIGNAL(WPDeleted(int,WayPointItem*)),this,SLOT(on_WPDeleted(int,WayPointItem*)),Qt::DirectConnection); - connect(myMap,SIGNAL(WPInserted(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); - connect(myMap,SIGNAL(WPCreated(int,WayPointItem*)),this,SLOT(on_WPInserted(int,WayPointItem*))); - connect(myMap,SIGNAL(WPNumberChanged(int,int,WayPointItem*)),this,SLOT(refreshOverlays())); - connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(refreshOverlays())); - } - -pathPlanManager::~pathPlanManager() -{ - delete ui; -} -void pathPlanManager::on_WPDeleted(int wp_numberint,WayPointItem * wp) -{ - QMutexLocker locker(&wplistmutex); - if(wp_numberint<0) - return; - waypoints->removeOne(wp); -} - -void pathPlanManager::on_WPInserted(int wp_number, WayPointItem * wp) -{ - if(waypoints->contains(wp)) - return; - wplistmutex.lock(); - waypoints->append(wp); - wplistmutex.unlock(); - wp->setWPType(WayPointItem::relative); - customData data; - data.mode=PathAction::MODE_FLYENDPOINT; - data.condition=PathAction::ENDCONDITION_NONE; - data.velocity=0; - QVariant var; - var.setValue(data); - wp->setData(0,var); - refreshOverlays(); -} - -void pathPlanManager::on_WPValuesChanged(WayPointItem * wp) -{ -} -//typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, -//MODE_FLYCIRCLELEFT=3, MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, -//MODE_DRIVECIRCLERIGHT=7, MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; -void pathPlanManager::refreshOverlays() -{ - QMutexLocker locker(&wplistmutex); - myMap->deleteAllOverlays(); - foreach(WayPointItem * wp,*waypoints) - { - customData data=wp->data(0).value(); - switch(data.mode) - { - case PathAction::MODE_FLYENDPOINT: - case PathAction::MODE_FLYVECTOR: - case PathAction::MODE_DRIVEENDPOINT: - case PathAction::MODE_DRIVEVECTOR: - if(wp->Number()==0) - myMap->WPLineCreate((HomeItem*)myMap->Home,wp); - else - myMap->WPLineCreate(findWayPointNumber(wp->Number()-1),wp); - break; - case PathAction::MODE_FLYCIRCLERIGHT: - case PathAction::MODE_DRIVECIRCLERIGHT: - if(wp->Number()==0) - myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,true); - myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,true); - break; - case PathAction::MODE_FLYCIRCLELEFT: - case PathAction::MODE_DRIVECIRCLELEFT: - if(wp->Number()==0) - myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,false); - myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,false); - break; - default: - break; - - } - } -} - -WayPointItem * pathPlanManager::findWayPointNumber(int number) -{ - if(number<0) - return NULL; - foreach(WayPointItem * wp,*waypoints) - { - if(wp->Number()==number) - return wp; - } - return NULL; -} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h deleted file mode 100644 index c17e61441..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.h +++ /dev/null @@ -1,61 +0,0 @@ -/** - ****************************************************************************** - * - * @file pathplanmanager.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PATHPLANMANAGER_H -#define PATHPLANMANAGER_H - -#include -#include "opmapcontrol/opmapcontrol.h" -#include "pathaction.h" -#include "waypoint.h" -#include "QMutexLocker" -#include "QPointer" - -namespace Ui { -class pathPlanManager; -} -using namespace mapcontrol; -class pathPlanManager : public QDialog -{ - Q_OBJECT -public: - explicit pathPlanManager(QWidget *parent,OPMapWidget * map); - ~pathPlanManager(); - WayPointItem *findWayPointNumber(int number); -private slots: - void refreshOverlays(); - void on_WPDeleted(int wp_numberint, WayPointItem *); - void on_WPInserted(int,WayPointItem*); - void on_WPValuesChanged(WayPointItem*); -private: - Ui::pathPlanManager *ui; - OPMapWidget * myMap; - QList > * waypoints; - QMutex wplistmutex; -}; - -#endif // PATHPLANMANAGER_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui b/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui deleted file mode 100644 index c8fbf92cb..000000000 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanmanager.ui +++ /dev/null @@ -1,21 +0,0 @@ - - - - - pathPlanManager - - - - 0 - 0 - 400 - 300 - - - - Form - - - - - diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp new file mode 100644 index 000000000..3f7ee9128 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -0,0 +1,93 @@ +#include "pathplanner.h" +#include "ui_pathplanner.h" +#include "widgetdelegates.h" +#include +#include + +pathPlanner::pathPlanner(QWidget *parent) : + QWidget(parent), + ui(new Ui::testTable),wid(NULL),myModel(NULL) +{ + ui->setupUi(this); +} + +pathPlanner::~pathPlanner() +{ + delete ui; + if(wid) + delete wid; +} +void pathPlanner::setModel(flightDataModel *model,QItemSelectionModel *selection) +{ + myModel=model; + ui->tableView->setModel(model); + ui->tableView->setSelectionModel(selection); + ui->tableView->setSelectionBehavior(QAbstractItemView::SelectRows); + ui->tableView->setItemDelegate(new ComboBoxDelegate(this)); + connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(on_rowsInserted(const QModelIndex&,int,int))); + wid=new opmap_edit_waypoint_dialog(NULL,model,selection); + ui->tableView->resizeColumnsToContents(); +} + +void pathPlanner::on_rowsInserted ( const QModelIndex & parent, int start, int end ) +{ + Q_UNUSED(parent); + for(int x=start;xtableView->model()->index(x,flightDataModel::MODE); + ui->tableView->openPersistentEditor(index); + index=ui->tableView->model()->index(x,flightDataModel::CONDITION); + ui->tableView->openPersistentEditor(index); + index=ui->tableView->model()->index(x,flightDataModel::COMMAND); + ui->tableView->openPersistentEditor(index); + ui->tableView->size().setHeight(10); + } +} + +void pathPlanner::on_tbAdd_clicked() +{ + ui->tableView->model()->insertRow(ui->tableView->model()->rowCount()); +} + +void pathPlanner::on_tbDelete_clicked() +{ + +} + +void pathPlanner::on_tbInsert_clicked() +{ + ui->tableView->model()->insertRow(ui->tableView->selectionModel()->currentIndex().row()); +} + +void pathPlanner::on_tbReadFromFile_clicked() +{ + if(!myModel) + return; + QString fileName = QFileDialog::getOpenFileName(this, tr("Open File")); + myModel->readFromFile(fileName); +} + +void pathPlanner::on_tbSaveToFile_clicked() +{ + if(!myModel) + return; + QString fileName = QFileDialog::getSaveFileName(this, tr("Save File")); + myModel->writeToFile(fileName); +} + +void pathPlanner::on_groupBox_clicked() +{ + +} + +void pathPlanner::on_groupBox_toggled(bool arg1) +{ + // wid->close(); + wid->setVisible(arg1); +} + +void pathPlanner::on_tbDetails_clicked() +{ + if(wid) + wid->show(); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h new file mode 100644 index 000000000..8498fa8d0 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h @@ -0,0 +1,45 @@ +#ifndef TESTTABLE_H +#define TESTTABLE_H + +#include +#include "flightdatamodel.h" +#include "opmap_edit_waypoint_dialog.h" +namespace Ui { +class testTable; +} + +class pathPlanner : public QWidget +{ + Q_OBJECT + +public: + explicit pathPlanner(QWidget *parent = 0); + ~pathPlanner(); + + void setModel(flightDataModel *model,QItemSelectionModel *selection); +private slots: + void on_rowsInserted ( const QModelIndex & parent, int start, int end ); + + void on_tbAdd_clicked(); + + void on_tbDelete_clicked(); + + void on_tbInsert_clicked(); + + void on_tbReadFromFile_clicked(); + + void on_tbSaveToFile_clicked(); + + void on_groupBox_clicked(); + + void on_groupBox_toggled(bool arg1); + + void on_tbDetails_clicked(); + +private: + Ui::testTable *ui; + opmap_edit_waypoint_dialog * wid; + flightDataModel * myModel; +}; + +#endif // TESTTABLE_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui new file mode 100644 index 000000000..6260af495 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui @@ -0,0 +1,131 @@ + + + testTable + + + + 0 + 0 + 536 + 262 + + + + Form + + + + + + + + Add Leg + + + ... + + + + :/opmap/images/plus3.png:/opmap/images/plus3.png + + + + + + + Delete Leg + + + ... + + + + :/opmap/images/stopb.png:/opmap/images/stopb.png + + + + + + + Insert Leg + + + ... + + + + :/opmap/images/forward_alt.png:/opmap/images/forward_alt.png + + + + + + + Read from file + + + ... + + + + :/opmap/images/unarchive.png:/opmap/images/unarchive.png + + + + + + + Save to file + + + ... + + + + :/opmap/images/Ekisho Deep Ocean HD1.png:/opmap/images/Ekisho Deep Ocean HD1.png + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Open Details + + + ... + + + + :/opmap/images/star.png:/opmap/images/star.png + + + + + + + + + QAbstractItemView::SelectRows + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp new file mode 100644 index 000000000..0a7517928 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -0,0 +1,133 @@ +#include "widgetdelegates.h" +#include +#include +#include +QWidget *ComboBoxDelegate::createEditor(QWidget *parent, + const QStyleOptionViewItem & option, + const QModelIndex & index) const +{ + int column=index.column(); + QComboBox * box; + switch(column) + { + case flightDataModel::MODE: + box=new QComboBox(parent); + ComboBoxDelegate::loadComboBox(box,flightDataModel::MODE); + return box; + break; + case flightDataModel::CONDITION: + box=new QComboBox(parent); + ComboBoxDelegate::loadComboBox(box,flightDataModel::CONDITION); + return box; + break; + + case flightDataModel::COMMAND: + box=new QComboBox(parent); + ComboBoxDelegate::loadComboBox(box,flightDataModel::COMMAND); + return box; + break; + default: + return QItemDelegate::createEditor(parent,option,index); + break; + } + + QComboBox *editor = new QComboBox(parent); + return editor; +} + +void ComboBoxDelegate::setEditorData(QWidget *editor, + const QModelIndex &index) const +{ + QString className=editor->metaObject()->className(); + if (className.contains("QComboBox")) { + int value = index.model()->data(index, Qt::EditRole).toInt(); + QComboBox *comboBox = static_cast(editor); + int x=comboBox->findData(value); + qDebug()<<"VALUE="<setCurrentIndex(x); + } + /* else if (className.contains("QRadioButton")) { + bool value = index.model()->data(index, Qt::EditRole).toBool(); + QRadioButton *radioButton = static_cast(editor); + radioButton->setChecked(value); + }*/ + else + QItemDelegate::setEditorData(editor, index); +} + +void ComboBoxDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const +{ + QString className=editor->metaObject()->className(); + if (className.contains("QComboBox")) { + QComboBox *comboBox = static_cast(editor); + int value = comboBox->itemData(comboBox->currentIndex()).toInt(); + model->setData(index, value, Qt::EditRole); + }/* + else if (className.contains("QRadioButton")) { + QRadioButton *radioButton = static_cast(editor); + bool value = radioButton->isChecked(); + model->setData(index, value, Qt::EditRole); + }*/ + else + QItemDelegate::setModelData(editor,model,index); +} + +void ComboBoxDelegate::updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &/* index */) const +{ + editor->setGeometry(option.rect); +} + +void ComboBoxDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDataEnum type) +{ + switch(type) + { + case flightDataModel::MODE: + combo->addItem("Fly Direct",MODE_FLYENDPOINT); + combo->addItem("Fly Vector",MODE_FLYVECTOR); + combo->addItem("Fly Circle Right",MODE_FLYCIRCLERIGHT); + combo->addItem("Fly Circle Left",MODE_FLYCIRCLELEFT); + + combo->addItem("Drive Direct",MODE_DRIVEENDPOINT); + combo->addItem("Drive Vector",MODE_DRIVEVECTOR); + combo->addItem("Drive Circle Right",MODE_DRIVECIRCLELEFT); + combo->addItem("Drive Circle Left",MODE_DRIVECIRCLERIGHT); + + combo->addItem("Fixed Attitude",MODE_FIXEDATTITUDE); + combo->addItem("Set Accessory",MODE_SETACCESSORY); + combo->addItem("Disarm Alarm",MODE_DISARMALARM); + break; + case flightDataModel::CONDITION: + combo->addItem("None",ENDCONDITION_NONE); + combo->addItem("Timeout",ENDCONDITION_TIMEOUT); + combo->addItem("Distance to tgt",ENDCONDITION_DISTANCETOTARGET); + combo->addItem("Leg remaining",ENDCONDITION_LEGREMAINING); + combo->addItem("Above Altitude",ENDCONDITION_ABOVEALTITUDE); + combo->addItem("Pointing towards next",ENDCONDITION_POINTINGTOWARDSNEXT); + combo->addItem("Python script",ENDCONDITION_PYTHONSCRIPT); + combo->addItem("Immediate",ENDCONDITION_IMMEDIATE); + break; + case flightDataModel::COMMAND: + combo->addItem("On conditon next wp",COMMAND_ONCONDITIONNEXTWAYPOINT); + combo->addItem("On NOT conditon next wp",COMMAND_ONNOTCONDITIONNEXTWAYPOINT); + combo->addItem("On conditon jump wp",COMMAND_ONCONDITIONJUMPWAYPOINT); + combo->addItem("On NOT conditon jump wp",COMMAND_ONNOTCONDITIONJUMPWAYPOINT); + combo->addItem("On conditon jump wp else next wp",COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT); + break; + default: + break; + } +} +/* +void ComboBoxDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const +{ + QStyleOptionComboBox opt; + opt.rect=option.rect; + QApplication::style()->drawComplexControl(QStyle::CC_ComboBox, &opt, + painter,createEditor(this,option,index)); +}*/ + +ComboBoxDelegate::ComboBoxDelegate(QObject *parent):QItemDelegate(parent) +{ +} diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h new file mode 100644 index 000000000..7e85ccabf --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h @@ -0,0 +1,38 @@ +#ifndef WIDGETDELEGATES_H +#define WIDGETDELEGATES_H +#include +#include +#include "flightdatamodel.h" + + +class ComboBoxDelegate : public QItemDelegate + { + Q_OBJECT + + public: + typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, + MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, + MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; + typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, + ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, + ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; + typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT=0, COMMAND_ONNOTCONDITIONNEXTWAYPOINT=1, + COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, + COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; + + ComboBoxDelegate(QObject *parent = 0); + + QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, + const QModelIndex &index) const; + + void setEditorData(QWidget *editor, const QModelIndex &index) const; + void setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const; + + void updateEditorGeometry(QWidget *editor, + const QStyleOptionViewItem &option, const QModelIndex &index) const; + static void loadComboBox(QComboBox * combo,flightDataModel::pathPlanDataEnum type); + //void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const; + }; + +#endif // WIDGETDELEGATES_H From 5d07b679227f8f77dfb98ca8a64e8ad2a6d632ef Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 17 Jun 2012 19:24:02 +0100 Subject: [PATCH 018/116] GCS/OPMap - pathplanner - graphical stuff and GUI done. UAVO interfacing left. --- .../src/mapwidget/opmapwidget.cpp | 21 ++- .../opmapcontrol/src/mapwidget/opmapwidget.h | 4 +- .../src/mapwidget/waypointcircle.cpp | 6 +- .../src/mapwidget/waypointline.cpp | 4 +- .../src/plugins/opmap/flightdatamodel.cpp | 2 +- .../src/plugins/opmap/modelmapproxy.cpp | 130 +++++++++++++----- .../src/plugins/opmap/modelmapproxy.h | 5 +- .../src/plugins/opmap/opmapgadget.cpp | 8 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 14 +- 9 files changed, 141 insertions(+), 53 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 4186f73e8..77193e5fd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -104,11 +104,11 @@ namespace mapcontrol GPS->SetUavPic(UAVPic); } - WayPointLine * OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to) + WayPointLine * OPMapWidget::WPLineCreate(WayPointItem *from, WayPointItem *to,QColor color) { if(!from|!to) return NULL; - return new WayPointLine(from,to,map); + return new WayPointLine(from,to,map,color); } WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to) { @@ -116,11 +116,11 @@ namespace mapcontrol return NULL; return new WayPointLine(from,to,map); } - WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise) + WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise,QColor color) { if(!center|!radius) return NULL; - return new WayPointCircle(center,radius,clockwise,map); + return new WayPointCircle(center,radius,clockwise,map,color); } WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise) @@ -290,11 +290,22 @@ namespace mapcontrol } WayPointItem* OPMapWidget::WPInsert(internals::PointLatLng const& coord,int const& altitude, QString const& description,const int &position) { - WayPointItem* item=new WayPointItem(coord,altitude,description,map); + internals::PointLatLng mcoord; + bool reloc=false; + if(mcoord==internals::PointLatLng(0,0)) + { + mcoord=CurrentPosition(); + reloc=true; + } + else + mcoord=coord; + WayPointItem* item=new WayPointItem(mcoord,altitude,description,map); item->SetNumber(position); ConnectWP(item); item->setParentItem(map); emit WPInserted(position,item); + if(reloc) + emit WPValuesChanged(item); return item; } void OPMapWidget::WPDelete(WayPointItem *item) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index b98b87ae1..862c1187e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -361,9 +361,9 @@ namespace mapcontrol bool ShowHome()const{return showhome;} void SetShowDiagnostics(bool const& value); void SetUavPic(QString UAVPic); - WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to); + WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to, QColor color); WayPointLine * WPLineCreate(HomeItem *from,WayPointItem *to); - WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise); + WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise,QColor color); WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise); void deleteAllOverlays(); void WPSetVisibleAll(bool value); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index 751d0788a..9bd99d407 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -34,8 +34,9 @@ namespace mapcontrol WayPointCircle::WayPointCircle(WayPointItem *center, WayPointItem *radius,bool clockwise, MapGraphicItem *map,QColor color):my_center(center), my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) { - connect(center,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(radius,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + qDebug()<<"circle clock:"<setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); - connect(from,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); - connect(to,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); + connect(from,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); + connect(to,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); connect(from,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); } diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index a8c6508fa..afb250389 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -22,7 +22,7 @@ QVariant flightDataModel::data(const QModelIndex &index, int role) const { int rowNumber=index.row(); int columnNumber=index.column(); - if(rowNumber>dataStorage.length()-1) + if(rowNumber>dataStorage.length()-1 || rowNumber<0) return QVariant(); pathPlanData * myRow=dataStorage.at(rowNumber); QVariant ret=getColumnByIndex(myRow,columnNumber); diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index edb2a8052..d4c44031e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -80,6 +80,51 @@ void modelMapProxy::on_selectedWPChanged(QList list) selection->setCurrentIndex(index,QItemSelectionModel::Select | QItemSelectionModel::Rows); } } + +modelMapProxy::overlayType modelMapProxy::overlayTranslate(int type) +{ + switch(type) + { + case ComboBoxDelegate::MODE_FLYENDPOINT: + case ComboBoxDelegate::MODE_FLYVECTOR: + case ComboBoxDelegate::MODE_DRIVEENDPOINT: + case ComboBoxDelegate::MODE_DRIVEVECTOR: + return OVERLAY_LINE; + break; + case ComboBoxDelegate::MODE_FLYCIRCLERIGHT: + case ComboBoxDelegate::MODE_DRIVECIRCLERIGHT: + return OVERLAY_CIRCLE_RIGHT; + break; + case ComboBoxDelegate::MODE_FLYCIRCLELEFT: + case ComboBoxDelegate::MODE_DRIVECIRCLELEFT: + return OVERLAY_CIRCLE_LEFT; + break; + default: + break; + } +} + +void modelMapProxy::createOverlay(WayPointItem *from, WayPointItem *to, modelMapProxy::overlayType type,QColor color) +{ + if(from==NULL || to==NULL || from==to) + return; + switch(type) + { + case OVERLAY_LINE: + myMap->WPLineCreate(from,to,color); + break; + case OVERLAY_CIRCLE_RIGHT: + myMap->WPCircleCreate(to,from,true,color); + break; + case OVERLAY_CIRCLE_LEFT: + myMap->WPCircleCreate(to,from,false,color); + break; + default: + break; + + } +} + /* typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, @@ -93,49 +138,61 @@ typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT=0, COMMAND_ONNOTCONDITIONNEXTWAYP */ void modelMapProxy::refreshOverlays() { - /* - QMutexLocker locker(&wplistmutex); + qDebug()<<"REFRESH OVERLAYS START"; myMap->deleteAllOverlays(); - foreach(WayPointItem * wp,*waypoints) + WayPointItem * wp_current=NULL; + WayPointItem * wp_next=NULL; + int wp_jump; + int wp_error; + overlayType wp_next_overlay; + overlayType wp_jump_overlay; + overlayType wp_error_overlay; + for(int x=0;xrowCount();++x) { - customData data=wp->data(0).value(); - - switch(data.condition) + qDebug()<<"REFRESH OVERLAYS WP:"<data(model->index(x,flightDataModel::JUMPDESTINATION)).toInt(); + wp_error=model->data(model->index(x,flightDataModel::ERRORDESTINATION)).toInt(); + wp_next_overlay=overlayTranslate(model->data(model->index(x+1,flightDataModel::MODE)).toInt()); + wp_jump_overlay=overlayTranslate(model->data(model->index(wp_jump,flightDataModel::MODE)).toInt()); + wp_error_overlay=overlayTranslate(model->data(model->index(wp_error,flightDataModel::MODE)).toInt()); + createOverlay(wp_current,findWayPointNumber(wp_error),wp_error_overlay,Qt::red); + switch(model->data(model->index(x,flightDataModel::COMMAND)).toInt()) { - - } - - switch(data.mode) - { - case PathAction::MODE_FLYENDPOINT: - case PathAction::MODE_FLYVECTOR: - case PathAction::MODE_DRIVEENDPOINT: - case PathAction::MODE_DRIVEVECTOR: - if(wp->Number()==0) - myMap->WPLineCreate((HomeItem*)myMap->Home,wp); - else - myMap->WPLineCreate(findWayPointNumber(wp->Number()-1),wp); + case ComboBoxDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: + wp_next=findWayPointNumber(x+1); + createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); + qDebug()<<"REFRESH OVERLAYS"<<"AKI0"; break; - case PathAction::MODE_FLYCIRCLERIGHT: - case PathAction::MODE_DRIVECIRCLERIGHT: - if(wp->Number()==0) - myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,true); - myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,true); + case ComboBoxDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: + wp_next=findWayPointNumber(wp_jump); + createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); + qDebug()<<"REFRESH OVERLAYS"<<"AKI1"; break; - case PathAction::MODE_FLYCIRCLELEFT: - case PathAction::MODE_DRIVECIRCLELEFT: - if(wp->Number()==0) - myMap->WPCircleCreate((HomeItem*)myMap->Home,wp,false); - myMap->WPCircleCreate(findWayPointNumber(wp->Number()-1),wp,false); + case ComboBoxDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: + wp_next=findWayPointNumber(wp_jump); + createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::yellow); + qDebug()<<"REFRESH OVERLAYS"<<"AKI2"; break; - default: + case ComboBoxDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: + wp_next=findWayPointNumber(x+1); + createOverlay(wp_current,wp_next,wp_next_overlay,Qt::yellow); + qDebug()<<"REFRESH OVERLAYS"<<"AKI3"; + break; + case ComboBoxDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: + wp_next=findWayPointNumber(wp_jump); + createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); + wp_next=findWayPointNumber(x+1); + createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); + qDebug()<<"REFRESH OVERLAYS"<<"AKI4"; break; - } } - */ } + + + WayPointItem * modelMapProxy::findWayPointNumber(int number) { if(number<0) @@ -158,6 +215,7 @@ void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int las { myMap->WPDelete(x); } + refreshOverlays(); } void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight) @@ -174,6 +232,13 @@ void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex QString desc; switch(topLeft.column()) { + case flightDataModel::COMMAND: + case flightDataModel::CONDITION: + case flightDataModel::JUMPDESTINATION: + case flightDataModel::ERRORDESTINATION: + case flightDataModel::MODE: + refreshOverlays(); + break; case flightDataModel::WPDESCRITPTION: index=model->index(x,flightDataModel::WPDESCRITPTION); desc=index.data(Qt::DisplayRole).toString(); @@ -250,6 +315,7 @@ void modelMapProxy::on_rowsInserted(const QModelIndex &parent, int first, int la if(relative) item->setWPType(mapcontrol::WayPointItem::relative); } + refreshOverlays(); } void modelMapProxy::deleteWayPoint(int number) { diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h index ec7e1e434..ad49e414a 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h @@ -8,12 +8,13 @@ #include "QPointer" #include "flightdatamodel.h" #include - +#include using namespace mapcontrol; class modelMapProxy:public QObject { + typedef enum {OVERLAY_LINE,OVERLAY_CIRCLE_RIGHT,OVERLAY_CIRCLE_LEFT} overlayType; Q_OBJECT public: explicit modelMapProxy(QObject *parent,OPMapWidget * map,flightDataModel * model,QItemSelectionModel * selectionModel); @@ -32,6 +33,8 @@ private slots: void on_currentRowChanged(QModelIndex,QModelIndex); void on_selectedWPChanged(QList); private: + overlayType overlayTranslate(int type); + void createOverlay(WayPointItem * from,WayPointItem * to,overlayType type,QColor color); OPMapWidget * myMap; flightDataModel * model; void refreshOverlays(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp index 388fd57bb..192575a55 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp @@ -52,16 +52,16 @@ void OPMapGadget::saveConfiguration(double lng,double lat,double zoom) void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) { m_config = qobject_cast(config); - m_widget->setMapProvider(m_config->mapProvider()); - m_widget->setZoom(m_config->zoom()); - m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); - m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); m_widget->setUseOpenGL(m_config->useOpenGL()); m_widget->setShowTileGridLines(m_config->showTileGridLines()); m_widget->setAccessMode(m_config->accessMode()); m_widget->setUseMemoryCache(m_config->useMemoryCache()); m_widget->setCacheLocation(m_config->cacheLocation()); m_widget->SetUavPic(m_config->uavSymbol()); + m_widget->setZoom(m_config->zoom()); + m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); + m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); + } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 6d105905c..f15ea146f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -212,17 +212,23 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - - +/* + qDebug()<<"here0"; model=new flightDataModel(this); + qDebug()<<"here1"; table=new pathPlanner(); + qDebug()<<"here2"; selectionModel=new QItemSelectionModel(model); + qDebug()<<"here3"; proxy=new modelMapProxy(this,m_map,model,selectionModel); + qDebug()<<"here4"; table->setModel(model,selectionModel); + qDebug()<<"here5"; table->show(); + qDebug()<<"here6"; waypoint_edit_dialog=new opmap_edit_waypoint_dialog(NULL,model,selectionModel); - - + qDebug()<<"here7"; +*/ /* distBearing db; db.distance=100; From 35cf2fe37418401899a8dc4b5a2b0b1aa4638412 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 17 Jun 2012 20:09:21 +0100 Subject: [PATCH 019/116] GCS/OPMap - pathplanner - added modelUavoProxy class. --- .../src/plugins/opmap/flightdatamodel.h | 1 + .../src/plugins/opmap/modeluavoproxy.cpp | 4 ++++ .../src/plugins/opmap/modeluavoproxy.h | 20 +++++++++++++++++++ .../openpilotgcs/src/plugins/opmap/opmap.pro | 6 ++++-- .../src/plugins/opmap/opmapgadgetwidget.cpp | 4 ++-- 5 files changed, 31 insertions(+), 4 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h index 58f56972a..b62f3164b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h @@ -25,6 +25,7 @@ struct pathPlanData class flightDataModel:public QAbstractTableModel { + Q_OBJECT public: enum pathPlanDataEnum { diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp new file mode 100644 index 000000000..207f9b002 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -0,0 +1,4 @@ +#include "modeluavoproxy.h" +modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model) +{ +} diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h new file mode 100644 index 000000000..024150c2e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h @@ -0,0 +1,20 @@ +#ifndef MODELUAVOPROXY_H +#define MODELUAVOPROXY_H + +#include +#include "flightdatamodel.h" +#include "pathaction.h" +#include "waypoint.h" + +class modelUavoProxy:public QObject +{ + Q_OBJECT +public: + explicit modelUavoProxy(QObject *parent, flightDataModel *model); +public slots: + void modelToObjects(); + void objectsToModel(); + +}; + +#endif // MODELUAVOPROXY_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index c571c3ca3..ab2df6030 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -21,7 +21,8 @@ HEADERS += opmapplugin.h \ flightdatamodel.h \ modelmapproxy.h \ widgetdelegates.h \ - pathplanner.h + pathplanner.h \ + modeluavoproxy.h SOURCES += opmapplugin.cpp \ opmapgadgetwidget.cpp \ @@ -35,7 +36,8 @@ SOURCES += opmapplugin.cpp \ flightdatamodel.cpp \ modelmapproxy.cpp \ widgetdelegates.cpp \ - pathplanner.cpp + pathplanner.cpp \ + modeluavoproxy.cpp OTHER_FILES += OPMapGadget.pluginspec diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index f15ea146f..0b5c45521 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -212,7 +212,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position -/* + qDebug()<<"here0"; model=new flightDataModel(this); qDebug()<<"here1"; @@ -228,7 +228,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) qDebug()<<"here6"; waypoint_edit_dialog=new opmap_edit_waypoint_dialog(NULL,model,selectionModel); qDebug()<<"here7"; -*/ + /* distBearing db; db.distance=100; From 88a089804b43bb5dcb48900f2bbb4f4125970f78 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 18 Jun 2012 00:16:23 +0100 Subject: [PATCH 020/116] GCS - added uavo per instance "new instance" signal. --- ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp | 8 ++++++++ ground/openpilotgcs/src/plugins/uavobjects/uavobject.h | 2 ++ .../src/plugins/uavobjects/uavobjectmanager.cpp | 2 ++ 3 files changed, 12 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp index 47960b060..330ec7bd3 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp @@ -469,6 +469,14 @@ void UAVObject::emitTransactionCompleted(bool success) emit transactionCompleted(this, success); } +/** + * Emit the newInstance event + */ +void UAVObject::emitNewInstance(UAVObject * obj) +{ + emit newInstance(obj); +} + /** * Initialize a UAVObjMetadata object. * \param[in] metadata The metadata object diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h index 945672c61..abe5f533b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h @@ -125,6 +125,7 @@ public: QString toStringBrief(); QString toStringData(); void emitTransactionCompleted(bool success); + void emitNewInstance(UAVObject *); // Metadata accessors static void MetadataInitialize(Metadata& meta); @@ -153,6 +154,7 @@ signals: void objectUnpacked(UAVObject* obj); void updateRequested(UAVObject* obj); void transactionCompleted(UAVObject* obj, bool success); + void newInstance(UAVObject* obj); private slots: void fieldUpdated(UAVObjectField* field); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp index c4f6f656e..5038b7bba 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp @@ -89,6 +89,7 @@ bool UAVObjectManager::registerObject(UAVDataObject* obj) UAVDataObject* cobj = obj->clone(instidx); cobj->initialize(mobj); objects[objidx].append(cobj); + getObject(cobj->getObjID())->emitNewInstance(cobj); emit newInstance(cobj); } // Finally, initialize the actual object instance @@ -105,6 +106,7 @@ bool UAVObjectManager::registerObject(UAVDataObject* obj) } // Add the actual object instance in the list objects[objidx].append(obj); + getObject(obj->getObjID())->emitNewInstance(obj); emit newInstance(obj); return true; } From 3cf4676aef9d821d02875de44e34b5e506f6b178 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 20 Jun 2012 14:58:33 +0100 Subject: [PATCH 021/116] GCS - OPMap - create doubleclick signal on the home item --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 11 +++++++++-- .../src/libs/opmapcontrol/src/mapwidget/homeitem.h | 12 +++++++----- 2 files changed, 16 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index dcbd0a58b..1b97aa8d0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -94,17 +94,24 @@ namespace mapcontrol coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); isDragging=false; - emit homePositionChanged(coord); + emit homePositionChanged(coord,Altitude()); } QGraphicsItem::mouseReleaseEvent(event); } + void HomeItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + emit homedoubleclick(this); + } + } void HomeItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) { if(isDragging) { coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - emit homePositionChanged(coord); + emit homePositionChanged(coord,Altitude()); } QGraphicsItem::mouseMoveEvent(event); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index f8003335b..8aab6a58c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -53,10 +53,10 @@ namespace mapcontrol int SafeArea()const{return safearea;} void SetSafeArea(int const& value){safearea=value;} bool safe; - void SetCoord(internals::PointLatLng const& value){emit homePositionChanged(value);coord=value;} + void SetCoord(internals::PointLatLng const& value){coord=value;emit homePositionChanged(value,Altitude());} internals::PointLatLng Coord()const{return coord;} - void SetAltitude(int const& value){altitude=value;} - int Altitude()const{return altitude;} + void SetAltitude(float const& value){altitude=value;emit homePositionChanged(Coord(),Altitude());} + float Altitude()const{return altitude;} private: MapGraphicItem* map; OPMapWidget* mapwidget; @@ -66,16 +66,18 @@ namespace mapcontrol bool showsafearea; int safearea; int localsafearea; - int altitude; + float altitude; bool isDragging; protected: void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); void mousePressEvent ( QGraphicsSceneMouseEvent * event ); void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); + void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); public slots: signals: - void homePositionChanged(internals::PointLatLng coord); + void homePositionChanged(internals::PointLatLng coord,float); + void homedoubleclick(HomeItem* waypoint); }; } #endif // HOMEITEM_H From 1299bbda938e3ea4c80d736a778f8f6ca7ab62ce Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 20 Jun 2012 14:59:23 +0100 Subject: [PATCH 022/116] GCS -OPMapLib - add relative altitude to waypoints --- .../src/mapwidget/opmapwidget.cpp | 13 ++++++-- .../opmapcontrol/src/mapwidget/opmapwidget.h | 5 +-- .../src/mapwidget/waypointcircle.cpp | 2 +- .../src/mapwidget/waypointitem.cpp | 31 ++++++++++++------- .../opmapcontrol/src/mapwidget/waypointitem.h | 19 ++++++------ .../src/mapwidget/waypointline.cpp | 2 +- 6 files changed, 46 insertions(+), 26 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 77193e5fd..f5356357c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -253,9 +253,9 @@ namespace mapcontrol emit WPCreated(position,item); return item; } - WayPointItem* OPMapWidget::WPCreate(const distBearing &relativeCoord, const int &altitude, const QString &description) + WayPointItem* OPMapWidget::WPCreate(const distBearingAltitude &relativeCoord, const QString &description) { - WayPointItem* item=new WayPointItem(relativeCoord,altitude,description,map); + WayPointItem* item=new WayPointItem(relativeCoord,description,map); ConnectWP(item); item->setParentItem(map); int position=item->Number(); @@ -308,6 +308,15 @@ namespace mapcontrol emit WPValuesChanged(item); return item; } + WayPointItem* OPMapWidget::WPInsert(distBearingAltitude const& relative, QString const& description,const int &position) + { + WayPointItem* item=new WayPointItem(relative,description,map); + item->SetNumber(position); + ConnectWP(item); + item->setParentItem(map); + emit WPInserted(position,item); + return item; + } void OPMapWidget::WPDelete(WayPointItem *item) { emit WPDeleted(item->Number(),item); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 862c1187e..b20ae3bfd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -289,7 +289,7 @@ namespace mapcontrol * @param description the description of the WayPoint * @return WayPointItem a pointer to the WayPoint created */ - WayPointItem *WPCreate(const distBearing &relativeCoord, const int &altitude, const QString &description); + WayPointItem *WPCreate(const distBearingAltitude &relativeCoord, const QString &description); /** * @brief Inserts a new WayPoint on the specified position * @@ -323,6 +323,7 @@ namespace mapcontrol * @return WayPointItem a pointer to the WayPoint Inserted */ WayPointItem* WPInsert(internals::PointLatLng const& coord,int const& altitude, QString const& description,int const& position); + WayPointItem *WPInsert(const distBearingAltitude &relative, const QString &description, const int &position); /** * @brief Deletes the WayPoint @@ -372,7 +373,7 @@ namespace mapcontrol void WPDelete(int number); WayPointItem *WPFind(int number); void setSelectedWP(QList list); - private: + private: internals::Core *core; MapGraphicItem *map; QGraphicsScene mscene; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index 9bd99d407..f6c5e23b6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -47,7 +47,7 @@ WayPointCircle::WayPointCircle(HomeItem *radius, WayPointItem *center, bool cloc my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) { qDebug()<<"circle clock:"<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); + } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); } @@ -62,6 +65,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals { relativeCoord.bearing=0; relativeCoord.distance=0; + relativeCoord.altitudeRelative=0; myType=relative; if(magicwaypoint) { @@ -93,7 +97,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals if(myHome) { coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); @@ -122,14 +127,14 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals if(myHome) { map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); - qDebug()<<"Waypoint CTOR distance"< list=map->childItems(); @@ -141,8 +146,9 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } if(myHome) { - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(onHomePositionChanged(internals::PointLatLng))); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); } myType=relative; text=0; @@ -250,16 +256,15 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } QGraphicsItem::mouseMoveEvent(event); } - void WayPointItem::SetAltitude(const int &value) + void WayPointItem::SetAltitude(const float &value) { altitude=value; RefreshToolTip(); - emit WPValuesChanged(this); this->update(); } - void WayPointItem::setRelativeCoord(distBearing value) + void WayPointItem::setRelativeCoord(distBearingAltitude value) { relativeCoord=value; if(myHome) @@ -279,7 +284,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals if(coord!=value) abs_coord=true; coord=value; - distBearing back=relativeCoord; + distBearingAltitude back=relativeCoord; qDebug()<<"SET COORD"<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); @@ -361,11 +366,12 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } } - void WayPointItem::onHomePositionChanged(internals::PointLatLng homepos) + void WayPointItem::onHomePositionChanged(internals::PointLatLng homepos, float homeAltitude) { if(myType==relative) { coord=map->Projection()->translate(homepos,relativeCoord.distance,relativeCoord.bearing); + SetAltitude(relativeCoord.altitudeRelative+homeAltitude); emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); @@ -374,7 +380,10 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals else { if(myHome) + { map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + relativeCoord.altitudeRelative=Altitude()-homeAltitude; + } emit WPValuesChanged(this); } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 2bb8fe7ef..57f9a7ce6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -37,10 +37,11 @@ namespace mapcontrol { -struct distBearing +struct distBearingAltitude { double distance; double bearing; + float altitudeRelative; double bearingToDegrees(){return bearing*180/M_PI;} void setBearingFromDegrees(double degrees){bearing=degrees*M_PI/180;} }; @@ -77,7 +78,7 @@ public: * @return */ WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map,wptype type=absolute); - WayPointItem(distBearing const& relativeCoord,int const& altitude,QString const& description,MapGraphicItem* map); + WayPointItem(distBearingAltitude const& relativeCoord,QString const& description,MapGraphicItem* map); /** * @brief Returns the WayPoint description @@ -141,15 +142,15 @@ public: * * @return int */ - int Altitude(){return altitude;} + float Altitude(){return altitude;} /** * @brief Sets the WayPoint Altitude * * @param value */ - void SetAltitude(int const& value); - void setRelativeCoord(distBearing value); - distBearing getRelativeCoord(){return relativeCoord;} + void SetAltitude(const float &value); + void setRelativeCoord(distBearingAltitude value); + distBearingAltitude getRelativeCoord(){return relativeCoord;} int type() const; QRectF boundingRect() const; void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, @@ -172,12 +173,12 @@ protected: void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); private: internals::PointLatLng coord;//coordinates of this WayPoint - distBearing relativeCoord; + distBearingAltitude relativeCoord; bool reached; QString description; bool shownumber; bool isDragging; - int altitude; + float altitude; MapGraphicItem* map; int number; @@ -214,7 +215,7 @@ public slots: */ void WPInserted(int const& number,WayPointItem* waypoint); - void onHomePositionChanged(internals::PointLatLng); + void onHomePositionChanged(internals::PointLatLng,float altitude); signals: /** * @brief fires when this WayPoint number changes (not fired if due to a auto-renumbering) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index b6d58e6eb..938d01246 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -45,7 +45,7 @@ WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map destination(to),my_map(map),QGraphicsLineItem(map),myColor(color) { this->setLine(to->pos().x(),to->pos().y(),from->pos().x(),from->pos().y()); - connect(from,SIGNAL(homePositionChanged(internals::PointLatLng)),this,SLOT(refreshLocations())); + connect(from,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(refreshLocations())); connect(to,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); } From b8b46e90a3b081269baebfc9b4f2ce0162db6e7a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 20 Jun 2012 15:00:15 +0100 Subject: [PATCH 023/116] GCS - OPMapLib - data model cleaning --- .../src/plugins/opmap/flightdatamodel.cpp | 61 +++++++++---- .../src/plugins/opmap/flightdatamodel.h | 3 +- .../src/plugins/opmap/modelmapproxy.cpp | 48 +++-------- .../src/plugins/opmap/modeluavoproxy.cpp | 85 ++++++++++++++++++- .../src/plugins/opmap/modeluavoproxy.h | 6 +- 5 files changed, 151 insertions(+), 52 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index afb250389..9740c50d0 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -11,25 +11,39 @@ int flightDataModel::rowCount(const QModelIndex &/*parent*/) const return dataStorage.length(); } -int flightDataModel::columnCount(const QModelIndex &/*parent*/) const +int flightDataModel::columnCount(const QModelIndex &parent) const { - return 22; + if (parent.isValid()) + return 0; + return 23; } QVariant flightDataModel::data(const QModelIndex &index, int role) const { if (role == Qt::DisplayRole||role==Qt::EditRole) - { - int rowNumber=index.row(); - int columnNumber=index.column(); - if(rowNumber>dataStorage.length()-1 || rowNumber<0) - return QVariant(); - pathPlanData * myRow=dataStorage.at(rowNumber); - QVariant ret=getColumnByIndex(myRow,columnNumber); - return ret; - } - return QVariant(); + { + int rowNumber=index.row(); + int columnNumber=index.column(); + if(rowNumber>dataStorage.length()-1 || rowNumber<0) + return QVariant::Invalid; + pathPlanData * myRow=dataStorage.at(rowNumber); + QVariant ret=getColumnByIndex(myRow,columnNumber); + return ret; + } + /* + else if (role == Qt::BackgroundRole) { + // WaypointActive::DataFields waypointActive = waypointActiveObj->getData(); + + if(index.row() == waypointActive.Index) { + return QBrush(Qt::lightGray); + } else + return QVariant::Invalid; + }*/ + else { + return QVariant::Invalid; + } } + bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const QVariant value) { switch(index) @@ -54,6 +68,10 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const row->beaRelative=value.toDouble(); return true; break; + case ALTITUDERELATIVE: + row->altitudeRelative=value.toFloat(); + return true; + break; case ISRELATIVE: row->isRelative=value.toDouble(); return true; @@ -144,6 +162,9 @@ QVariant flightDataModel::getColumnByIndex(const pathPlanData *row,const int ind case BEARELATIVE: return row->beaRelative; break; + case ALTITUDERELATIVE: + return row->altitudeRelative; + break; case ISRELATIVE: return row->isRelative; break; @@ -222,6 +243,9 @@ QVariant flightDataModel::headerData(int section, Qt::Orientation orientation, i case BEARELATIVE: return QString("Bearing from home"); break; + case ALTITUDERELATIVE: + return QString("Altitude above home"); + break; case ISRELATIVE: return QString("Relative to home"); break; @@ -279,13 +303,13 @@ QVariant flightDataModel::headerData(int section, Qt::Orientation orientation, i } } } - return QVariant(); + else + return QAbstractTableModel::headerData(section, orientation, role); } bool flightDataModel::setData(const QModelIndex &index, const QVariant &value, int role) { if (role == Qt::EditRole) { - //save value from editor to member m_gridData int columnIndex=index.column(); int rowIndex=index.row(); if(rowIndex>dataStorage.length()-1) @@ -293,7 +317,6 @@ bool flightDataModel::setData(const QModelIndex &index, const QVariant &value, i pathPlanData * myRow=dataStorage.at(rowIndex); setColumnByIndex(myRow,columnIndex,value); emit dataChanged(index,index); - //for presentation purposes only: build and emit a joined string } return true; } @@ -314,6 +337,7 @@ bool flightDataModel::insertRows(int row, int count, const QModelIndex &/*parent data->lngPosition=0; data->disRelative=0; data->beaRelative=0; + data->altitudeRelative=0; data->isRelative=0; data->altitude=0; data->velocity=0; @@ -392,6 +416,11 @@ bool flightDataModel::writeToFile(QString fileName) field.setAttribute("name","bearing_from_home"); waypoint.appendChild(field); + field=doc.createElement("field"); + field.setAttribute("value",obj->altitudeRelative); + field.setAttribute("name","altitude_above_home"); + waypoint.appendChild(field); + field=doc.createElement("field"); field.setAttribute("value",obj->isRelative); field.setAttribute("name","is_relative_to_home"); @@ -534,6 +563,8 @@ void flightDataModel::readFromFile(QString fileName) data->disRelative=field.attribute("value").toDouble(); else if(field.attribute("name")=="bearing_from_home") data->beaRelative=field.attribute("value").toDouble(); + else if(field.attribute("name")=="altitude_above_home") + data->altitudeRelative=field.attribute("value").toFloat(); else if(field.attribute("name")=="is_relative_to_home") data->isRelative=field.attribute("value").toInt(); else if(field.attribute("name")=="altitude") diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h index b62f3164b..d0040aa44 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h @@ -10,6 +10,7 @@ struct pathPlanData double lngPosition; double disRelative; double beaRelative; + double altitudeRelative; bool isRelative; double altitude; float velocity; @@ -29,7 +30,7 @@ class flightDataModel:public QAbstractTableModel public: enum pathPlanDataEnum { - WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, + WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ALTITUDERELATIVE,ISRELATIVE,ALTITUDE, VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, COMMAND,JUMPDESTINATION,ERRORDESTINATION,LOCKED diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index d4c44031e..35cbda7a0 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -59,6 +59,8 @@ void modelMapProxy::on_WPValuesChanged(WayPointItem * wp) model->setData(index,wp->getRelativeCoord().distance,Qt::EditRole); index=model->index(wp->Number(),flightDataModel::BEARELATIVE); model->setData(index,wp->getRelativeCoord().bearingToDegrees(),Qt::EditRole); + index=model->index(wp->Number(),flightDataModel::ALTITUDERELATIVE); + model->setData(index,wp->getRelativeCoord().altitudeRelative,Qt::EditRole); } void modelMapProxy::on_currentRowChanged(QModelIndex current, QModelIndex previous) @@ -125,20 +127,8 @@ void modelMapProxy::createOverlay(WayPointItem *from, WayPointItem *to, modelMap } } -/* -typedef enum { MODE_FLYENDPOINT=0, MODE_FLYVECTOR=1, MODE_FLYCIRCLERIGHT=2, MODE_FLYCIRCLELEFT=3, - MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, - MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; -typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, - ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, - ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; -typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT=0, COMMAND_ONNOTCONDITIONNEXTWAYPOINT=1, - COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, - COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; -*/ void modelMapProxy::refreshOverlays() { - qDebug()<<"REFRESH OVERLAYS START"; myMap->deleteAllOverlays(); WayPointItem * wp_current=NULL; WayPointItem * wp_next=NULL; @@ -149,7 +139,6 @@ void modelMapProxy::refreshOverlays() overlayType wp_error_overlay; for(int x=0;xrowCount();++x) { - qDebug()<<"REFRESH OVERLAYS WP:"<data(model->index(x,flightDataModel::JUMPDESTINATION)).toInt(); wp_error=model->data(model->index(x,flightDataModel::ERRORDESTINATION)).toInt(); @@ -162,50 +151,35 @@ void modelMapProxy::refreshOverlays() case ComboBoxDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); - qDebug()<<"REFRESH OVERLAYS"<<"AKI0"; break; case ComboBoxDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); - qDebug()<<"REFRESH OVERLAYS"<<"AKI1"; break; case ComboBoxDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::yellow); - qDebug()<<"REFRESH OVERLAYS"<<"AKI2"; break; case ComboBoxDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::yellow); - qDebug()<<"REFRESH OVERLAYS"<<"AKI3"; break; case ComboBoxDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); - qDebug()<<"REFRESH OVERLAYS"<<"AKI4"; break; } } } - - - WayPointItem * modelMapProxy::findWayPointNumber(int number) { if(number<0) return NULL; return myMap->WPFind(number); } -/* -WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, - VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, - CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, - COMMAND,JUMPDESTINATION,ERRORDESTINATION -*/ - void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int last) { @@ -225,7 +199,7 @@ void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex return; internals::PointLatLng latlng; int x=topLeft.row(); - distBearing distBearing; + distBearingAltitude distBearing; double altitude; bool relative; QModelIndex index; @@ -266,7 +240,11 @@ void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex index=model->index(x,flightDataModel::DISRELATIVE); distBearing.distance=index.data(Qt::DisplayRole).toDouble(); break; - + case flightDataModel::ALTITUDERELATIVE: + distBearing=item->getRelativeCoord(); + index=model->index(x,flightDataModel::ALTITUDERELATIVE); + distBearing.altitudeRelative=index.data(Qt::DisplayRole).toFloat(); + break; case flightDataModel::ISRELATIVE: index=model->index(x,flightDataModel::ISRELATIVE); relative=index.data(Qt::DisplayRole).toBool(); @@ -293,7 +271,7 @@ void modelMapProxy::on_rowsInserted(const QModelIndex &parent, int first, int la QModelIndex index; WayPointItem * item; internals::PointLatLng latlng; - distBearing distBearing; + distBearingAltitude distBearing; double altitude; bool relative; index=model->index(x,flightDataModel::WPDESCRITPTION); @@ -306,14 +284,16 @@ void modelMapProxy::on_rowsInserted(const QModelIndex &parent, int first, int la distBearing.distance=index.data(Qt::DisplayRole).toDouble(); index=model->index(x,flightDataModel::BEARELATIVE); distBearing.setBearingFromDegrees(index.data(Qt::DisplayRole).toDouble()); + index=model->index(x,flightDataModel::ALTITUDERELATIVE); + distBearing.altitudeRelative=index.data(Qt::DisplayRole).toFloat(); index=model->index(x,flightDataModel::ISRELATIVE); relative=index.data(Qt::DisplayRole).toBool(); index=model->index(x,flightDataModel::ALTITUDE); altitude=index.data(Qt::DisplayRole).toDouble(); - item=myMap->WPInsert(latlng,altitude,desc,x); - item->setRelativeCoord(distBearing); if(relative) - item->setWPType(mapcontrol::WayPointItem::relative); + item=myMap->WPInsert(distBearing,desc,x); + else + item=myMap->WPInsert(latlng,altitude,desc,x); } refreshOverlays(); } diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp index 207f9b002..1126c0670 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -1,4 +1,87 @@ #include "modeluavoproxy.h" -modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model) +#include "extensionsystem/pluginmanager.h" + +modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model):QObject(parent),myModel(model) +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm != NULL); + objManager = pm->getObject(); + Q_ASSERT(objManager != NULL); + waypointObj = Waypoint::GetInstance(objManager); + Q_ASSERT(waypointObj != NULL); + pathactionObj=PathAction::GetInstance(objManager); + Q_ASSERT(pathactionObj != NULL); +} +/*WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, + VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, + CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, + COMMAND,JUMPDESTINATION,ERRORDESTINATION,LOCKED + */ +void modelUavoProxy::modelToObjects() +{ + PathAction * act; + act=new PathAction; + Waypoint * wp; + wp=new Waypoint; + Q_ASSERT(act); + Q_ASSERT(wp); + Waypoint::DataFields waypoint = wp->getData(); + PathAction::DataFields action = act->getData(); + QModelIndex index; + double distance; + double bearing; + double altitude; + float velocity; + int mode; + int mode_param[4]; + int condition; + int cond_param[4]; + int command; + int jump; + int error; + for(int x=0;xrowCount();++x) + { + index=myModel->index(x,flightDataModel::DISRELATIVE); + distance=myModel->data(index).toDouble(); + index=myModel->index(x,flightDataModel::BEARELATIVE); + bearing=myModel->data(index).toDouble(); + index=myModel->index(x,flightDataModel::VELOCITY); + velocity=myModel->data(index).toFloat(); + + + index=myModel->index(x,flightDataModel::MODE); + mode=myModel->data(index).toInt(); + index=myModel->index(x,flightDataModel::MODE_PARAMS0); + mode_param[0]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::MODE_PARAMS1); + mode_param[1]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::MODE_PARAMS2); + mode_param[2]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::MODE_PARAMS3); + mode_param[3]=myModel->data(index).toFloat(); + + index=myModel->index(x,flightDataModel::CONDITION); + condition=myModel->data(index).toInt(); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS0); + cond_param[0]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS1); + cond_param[1]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS2); + cond_param[2]=myModel->data(index).toFloat(); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS3); + cond_param[3]=myModel->data(index).toFloat(); + + index=myModel->index(x,flightDataModel::COMMAND); + command=myModel->data(index).toInt(); + index=myModel->index(x,flightDataModel::JUMPDESTINATION); + jump=myModel->data(index).toInt(); + index=myModel->index(x,flightDataModel::ERRORDESTINATION); + error=myModel->data(index).toInt(); + + + } +} + +void modelUavoProxy::objectsToModel() { } diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h index 024150c2e..71390c08d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h @@ -14,7 +14,11 @@ public: public slots: void modelToObjects(); void objectsToModel(); - +private: + UAVObjectManager *objManager; + Waypoint * waypointObj; + PathAction * pathactionObj; + flightDataModel * myModel; }; #endif // MODELUAVOPROXY_H From 09a67af3e17e6b50f49b9fe546724c7d06431834 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 20 Jun 2012 15:01:03 +0100 Subject: [PATCH 024/116] GCS - MapLib - added home item editor --- .../src/plugins/opmap/homeeditor.cpp | 35 +++++ .../src/plugins/opmap/homeeditor.h | 31 ++++ .../src/plugins/opmap/homeeditor.ui | 136 ++++++++++++++++++ 3 files changed, 202 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp create mode 100644 ground/openpilotgcs/src/plugins/opmap/homeeditor.h create mode 100644 ground/openpilotgcs/src/plugins/opmap/homeeditor.ui diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp new file mode 100644 index 000000000..3e184fcb6 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp @@ -0,0 +1,35 @@ +#include "homeeditor.h" +#include "ui_homeeditor.h" + +homeEditor::homeEditor(HomeItem *home, QWidget *parent) : + QDialog(parent), + ui(new Ui::homeEditor), + myhome(home) +{ + if(!home) + { + deleteLater(); + return; + } + ui->setupUi(this); + this->setAttribute(Qt::WA_DeleteOnClose,true); + ui->altitude->setValue(home->Altitude()); + ui->latitude->setValue(home->Coord().Lat()); + ui->longitude->setValue(home->Coord().Lng()); +} + +homeEditor::~homeEditor() +{ + delete ui; +} + +void homeEditor::on_buttonBox_accepted() +{ + myhome->SetCoord(internals::PointLatLng(ui->latitude->value(),ui->longitude->value())); + myhome->SetAltitude(ui->altitude->value()); +} + +void homeEditor::on_buttonBox_rejected() +{ + this->close(); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.h b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h new file mode 100644 index 000000000..69a905edd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h @@ -0,0 +1,31 @@ +#ifndef HOMEEDITOR_H +#define HOMEEDITOR_H + +#include +#include "opmapcontrol/opmapcontrol.h" + +using namespace mapcontrol; + +namespace Ui { +class homeEditor; +} + +class homeEditor : public QDialog +{ + Q_OBJECT + +public: + explicit homeEditor(HomeItem * home,QWidget *parent = 0); + ~homeEditor(); + +private slots: + void on_buttonBox_accepted(); + + void on_buttonBox_rejected(); + +private: + Ui::homeEditor *ui; + HomeItem * myhome; +}; + +#endif // HOMEEDITOR_H diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui b/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui new file mode 100644 index 000000000..79cd6c84f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui @@ -0,0 +1,136 @@ + + + homeEditor + + + + 0 + 0 + 295 + 159 + + + + Dialog + + + + + + Latitude: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Longitude: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Altitude: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 999999999.000000000000000 + + + 0.100000000000000 + + + + + + + 999999999.000000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + 999999999.000000000000000 + + + 0.100000000000000 + + + + + + + Qt::Horizontal + + + QDialogButtonBox::Cancel|QDialogButtonBox::Ok + + + + + + + + + buttonBox + accepted() + homeEditor + accept() + + + 248 + 254 + + + 157 + 274 + + + + + buttonBox + rejected() + homeEditor + reject() + + + 316 + 260 + + + 286 + 274 + + + + + From 5216835e185ce4a8811fd089475e46f7b9a31d73 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 20 Jun 2012 15:02:57 +0100 Subject: [PATCH 025/116] GCS - OPMap - test functions --- .../openpilotgcs/src/plugins/opmap/opmap.pro | 9 +++++--- .../src/plugins/opmap/opmapgadgetwidget.cpp | 22 +++++++++++-------- .../src/plugins/opmap/opmapgadgetwidget.h | 2 +- .../src/plugins/uavobjects/uavobjects.pro | 10 +++++++-- 4 files changed, 28 insertions(+), 15 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.pro b/ground/openpilotgcs/src/plugins/opmap/opmap.pro index ab2df6030..6b30dfe97 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.pro +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.pro @@ -22,7 +22,8 @@ HEADERS += opmapplugin.h \ modelmapproxy.h \ widgetdelegates.h \ pathplanner.h \ - modeluavoproxy.h + modeluavoproxy.h \ + homeeditor.h SOURCES += opmapplugin.cpp \ opmapgadgetwidget.cpp \ @@ -37,7 +38,8 @@ SOURCES += opmapplugin.cpp \ modelmapproxy.cpp \ widgetdelegates.cpp \ pathplanner.cpp \ - modeluavoproxy.cpp + modeluavoproxy.cpp \ + homeeditor.cpp OTHER_FILES += OPMapGadget.pluginspec @@ -47,6 +49,7 @@ FORMS += opmapgadgetoptionspage.ui \ opmap_zoom_slider_widget.ui \ opmap_statusbar_widget.ui \ opmap_overlay_widget.ui \ - pathplanner.ui + pathplanner.ui \ + homeeditor.ui RESOURCES += opmap.qrc diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 0b5c45521..8a8f0429d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -840,7 +840,7 @@ void OPMapGadgetWidget::onTelemetryConnect() if (obum->getHomeLocation(set, LLA) < 0) return; // error - setHome(internals::PointLatLng(LLA[0], LLA[1])); + setHome(internals::PointLatLng(LLA[0], LLA[1]),LLA[2]); if (m_map) m_map->SetCurrentPosition(m_home_position.coord); // set the map position @@ -856,12 +856,14 @@ void OPMapGadgetWidget::onTelemetryDisconnect() // Updates the Home position icon whenever the HomePosition object is updated void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) { - if (!hp) - return; + Q_UNUSED(hp); + if (!obum) return; + bool set; + double LLA[3]; + if (obum->getHomeLocation(set, LLA) < 0) + return; // error + setHome(internals::PointLatLng(LLA[0], LLA[1]),LLA[2]); - double lat = hp->getField("Latitude")->getDouble() * 1e-7; - double lon = hp->getField("Longitude")->getDouble() * 1e-7; - setHome(internals::PointLatLng(lat, lon)); } // ************************************************************************************* @@ -888,13 +890,13 @@ void OPMapGadgetWidget::setHome(QPointF pos) else if (longitude < -180) longitude = -180; - setHome(internals::PointLatLng(latitude, longitude)); + setHome(internals::PointLatLng(latitude, longitude),0); } /** Sets the home position on the map widget */ -void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) +void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon,double altitude) { if (!m_widget || !m_map) return; @@ -916,12 +918,14 @@ void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) if (longitude > 180) longitude = 180; else if (longitude < -180) longitude = -180; + else if(altitude != altitude) altitude=0; // ********* m_home_position.coord = internals::PointLatLng(latitude, longitude); m_map->Home->SetCoord(m_home_position.coord); + m_map->Home->SetAltitude(altitude); m_map->Home->RefreshPos(); // move the magic waypoint to keep it within the safe area boundry @@ -1602,7 +1606,7 @@ void OPMapGadgetWidget::onSetHomeAct_triggered() if (!m_widget || !m_map) return; - setHome(m_context_menu_lat_lon); + setHome(m_context_menu_lat_lon,0); setHomeLocationObject(); // update the HomeLocation UAVObject } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index afb392a2d..0b60f4931 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -98,7 +98,7 @@ public: * @param */ void setHome(QPointF pos); - void setHome(internals::PointLatLng pos_lat_lon); + void setHome(internals::PointLatLng pos_lat_lon, double altitude); void goHome(); void setZoom(int zoom); void setPosition(QPointF pos); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index bfe2342b3..ba4e784df 100755 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -81,7 +81,10 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/cameradesired.h \ $$UAVOBJECT_SYNTHETICS/faultsettings.h \ $$UAVOBJECT_SYNTHETICS/pipxsettings.h \ - $$UAVOBJECT_SYNTHETICS/pipxstatus.h + $$UAVOBJECT_SYNTHETICS/pipxstatus.h \ + $$UAVOBJECT_SYNTHETICS/waypoint.h \ + $$UAVOBJECT_SYNTHETICS/waypointactive.h \ + $$UAVOBJECT_SYNTHETICS/pathaction.h SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/baroaltitude.cpp \ @@ -142,4 +145,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ $$UAVOBJECT_SYNTHETICS/faultsettings.cpp \ $$UAVOBJECT_SYNTHETICS/pipxsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/pipxstatus.cpp + $$UAVOBJECT_SYNTHETICS/pipxstatus.cpp \ + $$UAVOBJECT_SYNTHETICS/waypoint.cpp \ + $$UAVOBJECT_SYNTHETICS/waypointactive.cpp \ + $$UAVOBJECT_SYNTHETICS/pathaction.cpp From 2b9ad9dcb936e5249e5c6f2c5f887a447e018796 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 19:55:23 +0100 Subject: [PATCH 026/116] GCS - OPMap - Handle magic waypoint as special case with different picture. This is not used now but can be needed in the future --- .../src/mapwidget/waypointitem.cpp | 44 ++++++++++++++++--- .../opmapcontrol/src/mapwidget/waypointitem.h | 2 +- 2 files changed, 39 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 6e4a7d3ab..5b0aaaa2e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -33,6 +33,7 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu { text=0; numberI=0; + isMagic=false; picture.load(QString::fromUtf8(":/markers/images/marker.png")); number=WayPointItem::snumber; ++WayPointItem::snumber; @@ -69,11 +70,13 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals myType=relative; if(magicwaypoint) { + isMagic=true; picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); number=-1; } else { + isMagic=false; number=WayPointItem::snumber; ++WayPointItem::snumber; } @@ -107,6 +110,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals { text=0; numberI=0; + isMagic=false; picture.load(QString::fromUtf8(":/markers/images/marker.png")); number=WayPointItem::snumber; ++WayPointItem::snumber; @@ -153,6 +157,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals myType=relative; text=0; numberI=0; + isMagic=false; picture.load(QString::fromUtf8(":/markers/images/marker.png")); number=WayPointItem::snumber; ++WayPointItem::snumber; @@ -266,6 +271,11 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { + qDebug()<<"SET RELATIVE0"; + if(value.altitudeRelative==relativeCoord.altitudeRelative + && value.bearing==relativeCoord.bearing && value.distance==relativeCoord.distance) + return; + qDebug()<<"SET RELATIVE1"; relativeCoord=value; if(myHome) { @@ -273,12 +283,17 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } RefreshPos(); RefreshToolTip(); + emit WPValuesChanged(this); this->update(); } void WayPointItem::SetCoord(const internals::PointLatLng &value) { - if(this->WPType()==relative) + qDebug()<<"SET ABSOLUTE0"; + // if(this->WPType()==relative) + // return; + if(Coord()==value) return; + qDebug()<<"SET ABSOLUTE1"; bool abs_coord=false; bool rel_coord=false; if(coord!=value) @@ -298,6 +313,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } void WayPointItem::SetDescription(const QString &value) { + if(description==value) + return; description=value; RefreshToolTip(); emit WPValuesChanged(this); @@ -319,11 +336,21 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals emit WPValuesChanged(this); if(value) picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png")); - else if(this->flags() & QGraphicsItem::ItemIsMovable==QGraphicsItem::ItemIsMovable) - picture.load(QString::fromUtf8(":/markers/images/marker.png")); else - picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); - this->update(); + { + if(!isMagic) + { + if(this->flags() & QGraphicsItem::ItemIsMovable==QGraphicsItem::ItemIsMovable) + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + else + picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + } + else + { + picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + } + } + this->update(); } void WayPointItem::SetShowNumber(const bool &value) @@ -439,7 +466,12 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setFlag(QGraphicsItem::GraphicsItemFlag flag, bool enabled) { - if(flag==QGraphicsItem::ItemIsMovable) + if(isMagic) + { + QGraphicsItem::setFlag(flag,enabled); + return; + } + else if(flag==QGraphicsItem::ItemIsMovable) { if(enabled) picture.load(QString::fromUtf8(":/markers/images/marker.png")); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 57f9a7ce6..d90d1bf4b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -181,7 +181,7 @@ private: float altitude; MapGraphicItem* map; int number; - + bool isMagic; QGraphicsSimpleTextItem* text; QGraphicsRectItem* textBG; From e34fc5be713a67915c2a7f50da0c8ebf2eab6201 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 19:57:02 +0100 Subject: [PATCH 027/116] GCS - OPMap - allow different colors for overlays. This is so we can use a different color for each kind of route ex:error destination, jump destination, next destination --- .../src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp | 8 ++++---- .../src/libs/opmapcontrol/src/mapwidget/opmapwidget.h | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index f5356357c..9c0198a3d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -110,11 +110,11 @@ namespace mapcontrol return NULL; return new WayPointLine(from,to,map,color); } - WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to) + WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to,QColor color) { if(!from|!to) return NULL; - return new WayPointLine(from,to,map); + return new WayPointLine(from,to,map,color); } WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise,QColor color) { @@ -123,11 +123,11 @@ namespace mapcontrol return new WayPointCircle(center,radius,clockwise,map,color); } - WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise) + WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise,QColor color) { if(!center|!radius) return NULL; - return new WayPointCircle(center,radius,clockwise,map); + return new WayPointCircle(center,radius,clockwise,map,color); } void OPMapWidget::SetShowUAV(const bool &value) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index b20ae3bfd..98255e6fd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -363,9 +363,9 @@ namespace mapcontrol void SetShowDiagnostics(bool const& value); void SetUavPic(QString UAVPic); WayPointLine * WPLineCreate(WayPointItem *from,WayPointItem *to, QColor color); - WayPointLine * WPLineCreate(HomeItem *from,WayPointItem *to); + WayPointLine * WPLineCreate(HomeItem *from,WayPointItem *to, QColor color); WayPointCircle *WPCircleCreate(WayPointItem *center, WayPointItem *radius,bool clockwise,QColor color); - WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise); + WayPointCircle *WPCircleCreate(HomeItem *center, WayPointItem *radius,bool clockwise,QColor color); void deleteAllOverlays(); void WPSetVisibleAll(bool value); WayPointItem *magicWPCreate(); From 3466420a322bb2c4a048d74fdadc3a8f3610c488 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 19:58:09 +0100 Subject: [PATCH 028/116] GCS - OPMap - small changes to the home editor. --- .../openpilotgcs/src/plugins/opmap/homeeditor.cpp | 1 + .../openpilotgcs/src/plugins/opmap/homeeditor.ui | 15 +++++++++++++++ 2 files changed, 16 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp index 3e184fcb6..6c0ace86a 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp @@ -16,6 +16,7 @@ homeEditor::homeEditor(HomeItem *home, QWidget *parent) : ui->altitude->setValue(home->Altitude()); ui->latitude->setValue(home->Coord().Lat()); ui->longitude->setValue(home->Coord().Lng()); + this->show(); } homeEditor::~homeEditor() diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui b/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui index 79cd6c84f..98f5acc58 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.ui @@ -46,6 +46,9 @@ + + -999999999.000000000000000 + 999999999.000000000000000 @@ -56,6 +59,12 @@ + + 8 + + + -999999999.000000000000000 + 999999999.000000000000000 @@ -78,6 +87,12 @@ 0 + + 8 + + + -999999999.000000000000000 + 999999999.000000000000000 From ff48babb4651abebe30a0a6bb677cd3adad15d17 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 20:00:35 +0100 Subject: [PATCH 029/116] GCS/OPMap- Small visual changes to the pathplanner editor. Add buttons to synchronize planner data with UAVObjects. --- .../src/plugins/opmap/images/down_alt2.png | Bin 0 -> 2256 bytes .../src/plugins/opmap/pathplanner.cpp | 10 +++++ .../src/plugins/opmap/pathplanner.h | 7 ++++ .../src/plugins/opmap/pathplanner.ui | 35 +++++++++++++++++- 4 files changed, 51 insertions(+), 1 deletion(-) create mode 100644 ground/openpilotgcs/src/plugins/opmap/images/down_alt2.png diff --git a/ground/openpilotgcs/src/plugins/opmap/images/down_alt2.png b/ground/openpilotgcs/src/plugins/opmap/images/down_alt2.png new file mode 100644 index 0000000000000000000000000000000000000000..b7713552696c50ea6aefc87a513dcf819199687f GIT binary patch literal 2256 zcmV;>2ru`EP)4Tx0C=3`m1|6scNE5-_w601v`~vo(O1S0Sz#TZtU?ITAp;SxRG^G>_9j$Y zc=J*bWK$VN@P-$d%EE>c6qRf)C=MCU8xx|5L(GujykIrn5O0G7M7s}Njf8lNZ<)iouPn^Nli_{TWh2j1OQwP z($Tb~DQUjxX6yC&z61IVkB$c!-`)oR5HgvXEP$W@NOGJy41h%M)Sm&6thCWKfXD_Q zG34ru06_zgF=~|(AZh`O=crXmfZPpWT(4Fs0ai7D@j^q64Pb8rAkQ1 zfHvub_k0Ej0K_Lh7c3180RRxz*x?xO0XQIUh=6a7#?eN(;BXuU*x81MAKQ_R9_U#W(2krl;>f?&g@;Q~^ zdlc;v_9$s|dTjltFXERZ^dzMu_bsxj-O^h$=4^lMpsvlhEyuDf#Trig6-WwsMdKw; zSKleUvaYMVb>o38ySG(TmF%Qz%(YAF%=OH^vIE~Yb^JKo9M)3SYHweB^4i%IoznAX zE*AGh_6q+Tyw*R^cjw*%*P)naTSlI|SnhDVal0F)LXHKn;u~~el$cAbBF>TCq>b!j z#j)Dh3ifGE8s{;0CvQHV;CBjkxiGF7Zt=pHNpbEfky%{n(IIi2te2jj664)9RqI1c zKSI&Ik$ztO#H_JE$Rxp`a&1Ue*rjl(LLbo_#g5L5JsRf|UzIpHsXirQ(GB&MjJPaL z_Qfy0(-)YMbAy+QtiyDF!LNmTi`RasStBbQS$C}5x^dd(-?rxN;8i#5imtg{ySmPA z@1=(F#>7L@e!$_;BZ6adj<0DSJhi4Hp!3Fs#^1{?mtCp5YQLFwd-#6$(8IrzMqj*f zI|%_Kcpu?NMILtG7d#*+BAeJlJS3yY8uBG;Im^yAvY&D)xPjb0-gbV5Ai#y=GUR&8 zZ9q8a4v~*o<#}W!I{MUu{~O zSC+g!a07eO)yn4W71c|2DZcfp9jmj~|FN(8Kws0N!ye5EE!C|f?aV2`*`uAyE(Be4 z^w@j<>VJ4cV%OX~F&Ovc*>Km`1&71Qs*@1sp8^2)N+niwiWA1B>mz zf^$GkBH$khcp8CJA)r=(xMct_FcZWBF<2-9`L0p*u95Vv(E~U$4FDiAFVq<*rOsm3 zGdi2;bqtGO#zN>|00kvb0h+G~D0M6V60ImqA%>sZE&$MsM{ReJ$+fbtBPe1?w1GPy+K~z|U z?UvtbTV)u>KRI2JwriH1IdN7u8DiUXsUqT?BNW9uuiU>NbAq5Zq6~H+2!(>8h;!;D zc;m%zcOndQN!y9rItR+wmA1`kv$k1n(!`VVpYuF# za$fj<{l_a7RXF+1eIFSy<3v=w((3f3lN+z}1mL+TGo4DLE9YK*8&|A{>XY#U9DDb5 zzCBqE_1_f*006CNh!VC}440xn>qxed0kqaAB~eO*YNeLwUIU;(X^GI`07^-Smj5?8 zpfpnY2JE! z_)>t1l#dZbbpAY2Dv6K+Pq?8ah>bF>_%!ivA zM(+WdzXFXX!i|O0|9k|wSNl&9GfrS|005<_In_u2HKz(nlY4EjDb~7=#Qtkf9NsJUig~D z((2Lt`;EDFZC^Ko;&saVGp@e1XiXkGn8vEyq+DOY@g1Zhv>e~1VsB7$t0enOzWQdK z#ii18;Y0UqXI57LfTej^FtftAU8?7v96LhYuiy#~sha2OUZr)6WPFH+(pfI$ixi8u zrwbo@ceVeX007oCkvETc#@ec#dtx+0-K*jV7pe5NPp?#r#I7M8PG>0;EQ-sk(=%tf zhlc_HSo1P(W;|nk)y_RWnxW=y1rXiClkpUX_D(Q2Q^ZPxH^&^~ z&YGQ@7#pYV{RPq9_JKr-N6aig%r3HItxnB-=D!){9SH!y`cdW0jB9L`?Ob+bj4iK< z2AA@(nd>9&W^|8_qM?%s2|oA#;SQgdh)4f`R?L1mKMrqu6(IJ08&Bi2Ks?S z8%Wo%&SlX2i|!9hI?ei8PdM?s@#5ZLUaFM%^yiD}0w8H#MFijjF7P{02Wo&5?CYSq z0>lD<1TX*$2I0w|EA8zyg3mHAYyrps!V5y}pxidiwjF5gw+Hlf?8Ufywz{KKTgkTI eh!^&MY5f7RH%4show(); } + +void pathPlanner::on_tbSendToUAV_clicked() +{ + emit sendPathPlanToUAV(); +} + +void pathPlanner::on_tbFetchFromUAV_clicked() +{ + emit receivePathPlanFromUAV(); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h index 8498fa8d0..2b7d270c7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h @@ -36,10 +36,17 @@ private slots: void on_tbDetails_clicked(); + void on_tbSendToUAV_clicked(); + + void on_tbFetchFromUAV_clicked(); + private: Ui::testTable *ui; opmap_edit_waypoint_dialog * wid; flightDataModel * myModel; +signals: + void sendPathPlanToUAV(); + void receivePathPlanFromUAV(); }; #endif // TESTTABLE_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui index 6260af495..e5cfd5488 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui @@ -11,7 +11,11 @@ - Form + PathPlanner + + + + :/core/images/openpilot_logo_64.png:/core/images/openpilot_logo_64.png @@ -86,6 +90,34 @@ + + + + Send to UAV + + + ... + + + + :/opmap/images/up_alt.png:/opmap/images/up_alt.png + + + + + + + Fetch from UAV + + + ... + + + + :/opmap/images/down_alt.png:/opmap/images/down_alt.png + + + @@ -125,6 +157,7 @@ + From 2b85f1a9fdc413d26a2b417659812fea96c990b8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 20:02:45 +0100 Subject: [PATCH 030/116] GCS/OPMap- Bugfixes to the model/map proxy. Dynamic overlay creation based on the path plan actions. --- .../src/plugins/opmap/modelmapproxy.cpp | 35 +++++++++++++++++-- .../src/plugins/opmap/modelmapproxy.h | 1 + 2 files changed, 33 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index 35cbda7a0..48d78a34c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -126,10 +126,31 @@ void modelMapProxy::createOverlay(WayPointItem *from, WayPointItem *to, modelMap } } +void modelMapProxy::createOverlay(WayPointItem *from, HomeItem *to, modelMapProxy::overlayType type,QColor color) +{ + if(from==NULL || to==NULL) + return; + switch(type) + { + case OVERLAY_LINE: + myMap->WPLineCreate(to,from,color); + break; + case OVERLAY_CIRCLE_RIGHT: + myMap->WPCircleCreate(to,from,true,color); + break; + case OVERLAY_CIRCLE_LEFT: + myMap->WPCircleCreate(to,from,false,color); + break; + default: + break; + } +} void modelMapProxy::refreshOverlays() { myMap->deleteAllOverlays(); + if(model->rowCount()<1) + return; WayPointItem * wp_current=NULL; WayPointItem * wp_next=NULL; int wp_jump; @@ -137,15 +158,18 @@ void modelMapProxy::refreshOverlays() overlayType wp_next_overlay; overlayType wp_jump_overlay; overlayType wp_error_overlay; + wp_current=findWayPointNumber(0); + overlayType wp_current_overlay=overlayTranslate(model->data(model->index(0,flightDataModel::MODE)).toInt()); + createOverlay(wp_current,myMap->Home,wp_current_overlay,Qt::green); for(int x=0;xrowCount();++x) { wp_current=findWayPointNumber(x); wp_jump=model->data(model->index(x,flightDataModel::JUMPDESTINATION)).toInt(); wp_error=model->data(model->index(x,flightDataModel::ERRORDESTINATION)).toInt(); wp_next_overlay=overlayTranslate(model->data(model->index(x+1,flightDataModel::MODE)).toInt()); - wp_jump_overlay=overlayTranslate(model->data(model->index(wp_jump,flightDataModel::MODE)).toInt()); - wp_error_overlay=overlayTranslate(model->data(model->index(wp_error,flightDataModel::MODE)).toInt()); - createOverlay(wp_current,findWayPointNumber(wp_error),wp_error_overlay,Qt::red); + wp_jump_overlay=overlayTranslate(model->data(model->index(wp_jump,flightDataModel::MODE)).toInt()); + wp_error_overlay=overlayTranslate(model->data(model->index(wp_error,flightDataModel::MODE)).toInt()); + createOverlay(wp_current,findWayPointNumber(wp_error),wp_error_overlay,Qt::red); switch(model->data(model->index(x,flightDataModel::COMMAND)).toInt()) { case ComboBoxDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: @@ -234,22 +258,27 @@ void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex distBearing=item->getRelativeCoord(); index=model->index(x,flightDataModel::BEARELATIVE); distBearing.setBearingFromDegrees(index.data(Qt::DisplayRole).toDouble()); + item->setRelativeCoord(distBearing); break; case flightDataModel::DISRELATIVE: distBearing=item->getRelativeCoord(); index=model->index(x,flightDataModel::DISRELATIVE); distBearing.distance=index.data(Qt::DisplayRole).toDouble(); + item->setRelativeCoord(distBearing); break; case flightDataModel::ALTITUDERELATIVE: distBearing=item->getRelativeCoord(); index=model->index(x,flightDataModel::ALTITUDERELATIVE); distBearing.altitudeRelative=index.data(Qt::DisplayRole).toFloat(); + item->setRelativeCoord(distBearing); break; case flightDataModel::ISRELATIVE: index=model->index(x,flightDataModel::ISRELATIVE); relative=index.data(Qt::DisplayRole).toBool(); if(relative) item->setWPType(mapcontrol::WayPointItem::relative); + else + item->setWPType(mapcontrol::WayPointItem::absolute); break; case flightDataModel::ALTITUDE: index=model->index(x,flightDataModel::ALTITUDE); diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h index ad49e414a..c6bcaf076 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h @@ -35,6 +35,7 @@ private slots: private: overlayType overlayTranslate(int type); void createOverlay(WayPointItem * from,WayPointItem * to,overlayType type,QColor color); + void createOverlay(WayPointItem *from, HomeItem *to, modelMapProxy::overlayType type, QColor color); OPMapWidget * myMap; flightDataModel * model; void refreshOverlays(); From b84af5c3386602799a62c0103a49dee8fe3c47aa Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 24 Jun 2012 20:04:13 +0100 Subject: [PATCH 031/116] GCS/OPMap-Model/UAVO proxy class. Handles the convertion between flight plan data from the model to/from UAVObjects. --- .../src/plugins/opmap/modeluavoproxy.cpp | 224 +++++++++++++++--- .../src/plugins/opmap/modeluavoproxy.h | 1 + 2 files changed, 193 insertions(+), 32 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp index 1126c0670..e8b07bb23 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -1,6 +1,6 @@ #include "modeluavoproxy.h" #include "extensionsystem/pluginmanager.h" - +#include modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model):QObject(parent),myModel(model) { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -11,6 +11,26 @@ modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model):QObject( Q_ASSERT(waypointObj != NULL); pathactionObj=PathAction::GetInstance(objManager); Q_ASSERT(pathactionObj != NULL); + + /* + int instances=objManager->getNumInstances(pathactionObj->getObjID()); + PathAction * actionObj=new PathAction; + actionObj->initialize(instances,actionObj->getMetaObject()); + objManager->registerObject(actionObj); + actionObj->updated(); + + instances=objManager->getNumInstances(pathactionObj->getObjID()); + actionObj=new PathAction; + actionObj->initialize(instances,actionObj->getMetaObject()); + objManager->registerObject(actionObj); + actionObj->updated(); + + instances=objManager->getNumInstances(pathactionObj->getObjID()); + actionObj=new PathAction; + actionObj->initialize(instances,actionObj->getMetaObject()); + objManager->registerObject(actionObj); + actionObj->updated(); + */ } /*WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, @@ -19,69 +39,209 @@ modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model):QObject( */ void modelUavoProxy::modelToObjects() { - PathAction * act; - act=new PathAction; - Waypoint * wp; - wp=new Waypoint; - Q_ASSERT(act); - Q_ASSERT(wp); - Waypoint::DataFields waypoint = wp->getData(); - PathAction::DataFields action = act->getData(); + PathAction * act=NULL; + Waypoint * wp=NULL; QModelIndex index; double distance; double bearing; double altitude; - float velocity; - int mode; - int mode_param[4]; - int condition; - int cond_param[4]; - int command; - int jump; - int error; + int lastaction=-1; for(int x=0;xrowCount();++x) { + int instances=objManager->getNumInstances(waypointObj->getObjID()); + if(x>instances-1) + { + wp=new Waypoint; + wp->initialize(x,wp->getMetaObject()); + objManager->registerObject(wp); + } + else + { + wp=Waypoint::GetInstance(objManager,x); + } + act=new PathAction; + Q_ASSERT(act); + Q_ASSERT(wp); + Waypoint::DataFields waypoint = wp->getData(); + PathAction::DataFields action = act->getData(); + + ///Waypoint object data index=myModel->index(x,flightDataModel::DISRELATIVE); distance=myModel->data(index).toDouble(); index=myModel->index(x,flightDataModel::BEARELATIVE); bearing=myModel->data(index).toDouble(); + index=myModel->index(x,flightDataModel::ALTITUDERELATIVE); + altitude=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::VELOCITY); - velocity=myModel->data(index).toFloat(); + waypoint.Velocity=myModel->data(index).toFloat(); + waypoint.Position[Waypoint::POSITION_NORTH]=distance*cos(bearing/180*M_PI); + waypoint.Position[Waypoint::POSITION_EAST]=distance*sin(bearing/180*M_PI); + waypoint.Position[Waypoint::POSITION_DOWN]=(-1.0f)*altitude; + ///PathAction object data index=myModel->index(x,flightDataModel::MODE); - mode=myModel->data(index).toInt(); + action.Mode=myModel->data(index).toInt(); index=myModel->index(x,flightDataModel::MODE_PARAMS0); - mode_param[0]=myModel->data(index).toFloat(); + action.ModeParameters[0]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::MODE_PARAMS1); - mode_param[1]=myModel->data(index).toFloat(); + action.ModeParameters[1]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::MODE_PARAMS2); - mode_param[2]=myModel->data(index).toFloat(); + action.ModeParameters[2]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::MODE_PARAMS3); - mode_param[3]=myModel->data(index).toFloat(); + action.ModeParameters[3]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::CONDITION); - condition=myModel->data(index).toInt(); + action.EndCondition=myModel->data(index).toInt(); index=myModel->index(x,flightDataModel::CONDITION_PARAMS0); - cond_param[0]=myModel->data(index).toFloat(); + action.ConditionParameters[0]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::CONDITION_PARAMS1); - cond_param[1]=myModel->data(index).toFloat(); + action.ConditionParameters[1]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::CONDITION_PARAMS2); - cond_param[2]=myModel->data(index).toFloat(); + action.ConditionParameters[2]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::CONDITION_PARAMS3); - cond_param[3]=myModel->data(index).toFloat(); + action.ConditionParameters[3]=myModel->data(index).toFloat(); index=myModel->index(x,flightDataModel::COMMAND); - command=myModel->data(index).toInt(); + action.Command=myModel->data(index).toInt(); index=myModel->index(x,flightDataModel::JUMPDESTINATION); - jump=myModel->data(index).toInt(); + action.JumpDestination=myModel->data(index).toInt(); index=myModel->index(x,flightDataModel::ERRORDESTINATION); - error=myModel->data(index).toInt(); - + action.ErrorDestination=myModel->data(index).toInt(); + int actionNumber=addAction(act,action,lastaction); + if(actionNumber>lastaction) + lastaction=actionNumber; + waypoint.Action=actionNumber; + wp->setData(waypoint); + wp->updated(); } } void modelUavoProxy::objectsToModel() { + Waypoint * wp; + Waypoint::DataFields wpfields; + PathAction * action; + QModelIndex index; + double distance; + double bearing; + + PathAction::DataFields actionfields; + + myModel->removeRows(0,myModel->rowCount()); + for(int x=0;xgetNumInstances(waypointObj->getObjID());++x) + { + wp=Waypoint::GetInstance(objManager,x); + Q_ASSERT(wp); + if(!wp) + continue; + wpfields=wp->getData(); + myModel->insertRow(x); + index=myModel->index(x,flightDataModel::VELOCITY); + myModel->setData(index,wpfields.Velocity); + distance=sqrt(wpfields.Position[Waypoint::POSITION_NORTH]*wpfields.Position[Waypoint::POSITION_NORTH]+ + wpfields.Position[Waypoint::POSITION_EAST]*wpfields.Position[Waypoint::POSITION_EAST]); + bearing=acos(wpfields.Position[Waypoint::POSITION_NORTH]/wpfields.Position[Waypoint::POSITION_EAST])*180/M_PI; + if(bearing!=bearing) + bearing=0; + index=myModel->index(x,flightDataModel::DISRELATIVE); + myModel->setData(index,distance); + index=myModel->index(x,flightDataModel::BEARELATIVE); + myModel->setData(index,bearing); + index=myModel->index(x,flightDataModel::ALTITUDERELATIVE); + myModel->setData(index,(-1.0f)*wpfields.Position[Waypoint::POSITION_DOWN]); + + action=PathAction::GetInstance(objManager,wpfields.Action); + Q_ASSERT(action); + if(!action) + continue; + actionfields=action->getData(); + + index=myModel->index(x,flightDataModel::ISRELATIVE); + myModel->setData(index,true); + + index=myModel->index(x,flightDataModel::COMMAND); + myModel->setData(index,actionfields.Command); + + index=myModel->index(x,flightDataModel::CONDITION_PARAMS0); + myModel->setData(index,actionfields.ConditionParameters[0]); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS1); + myModel->setData(index,actionfields.ConditionParameters[1]); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS2); + myModel->setData(index,actionfields.ConditionParameters[2]); + index=myModel->index(x,flightDataModel::CONDITION_PARAMS3); + myModel->setData(index,actionfields.ConditionParameters[3]); + + index=myModel->index(x,flightDataModel::CONDITION); + myModel->setData(index,actionfields.EndCondition); + + index=myModel->index(x,flightDataModel::ERRORDESTINATION); + myModel->setData(index,actionfields.ErrorDestination); + + index=myModel->index(x,flightDataModel::JUMPDESTINATION); + myModel->setData(index,actionfields.JumpDestination); + + index=myModel->index(x,flightDataModel::MODE); + myModel->setData(index,actionfields.Mode); + + index=myModel->index(x,flightDataModel::MODE_PARAMS0); + myModel->setData(index,actionfields.ModeParameters[0]); + index=myModel->index(x,flightDataModel::MODE_PARAMS1); + myModel->setData(index,actionfields.ModeParameters[1]); + index=myModel->index(x,flightDataModel::MODE_PARAMS2); + myModel->setData(index,actionfields.ModeParameters[2]); + index=myModel->index(x,flightDataModel::MODE_PARAMS3); + myModel->setData(index,actionfields.ModeParameters[3]); + } +} +int modelUavoProxy::addAction(PathAction * actionObj,PathAction::DataFields actionFields,int lastaction) +{ + //check if a similar action already exhists + int instances=objManager->getNumInstances(pathactionObj->getObjID()); + for(int x=0;xgetData(); + if(fields.Command==actionFields.Command + && fields.ConditionParameters[0]==actionFields.ConditionParameters[0] + && fields.ConditionParameters[1]==actionFields.ConditionParameters[1] + && fields.ConditionParameters[2]==actionFields.ConditionParameters[2] + &&fields.EndCondition==actionFields.EndCondition + &&fields.ErrorDestination==actionFields.ErrorDestination + &&fields.JumpDestination==actionFields.JumpDestination + &&fields.Mode==actionFields.Mode + &&fields.ModeParameters[0]==actionFields.ModeParameters[0] + &&fields.ModeParameters[1]==actionFields.ModeParameters[1] + &&fields.ModeParameters[2]==actionFields.ModeParameters[2]) + { + qDebug()<<"ModelUAVProxy:"<<"found similar action instance:"<deleteLater(); + return x; + } + } + //if we get here it means no similar action was found, we have to create it + if(instancesinitialize(instances,actionObj->getMetaObject()); + objManager->registerObject(actionObj); + actionObj->setData(actionFields); + actionObj->updated(); + qDebug()<<"ModelUAVProxy:"<<"created new action instance:"<setData(actionFields); + action->updated(); + actionObj->deleteLater(); + qDebug()<<"ModelUAVProxy:"<<"reused action instance:"< Date: Sun, 24 Jun 2012 20:05:27 +0100 Subject: [PATCH 032/116] GCS/OPMap- handles home icon doubleclick. Visual changes to the waypoint editor. --- .../openpilotgcs/src/plugins/opmap/opmap.qrc | 1 + .../opmap/opmap_edit_waypoint_dialog.ui | 108 +++++++++++------- .../src/plugins/opmap/opmapgadgetwidget.cpp | 66 +++++------ .../src/plugins/opmap/opmapgadgetwidget.h | 12 +- 4 files changed, 108 insertions(+), 79 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap.qrc b/ground/openpilotgcs/src/plugins/opmap/opmap.qrc index 99ff510f5..10073e59e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap.qrc +++ b/ground/openpilotgcs/src/plugins/opmap/opmap.qrc @@ -35,5 +35,6 @@ images/plus3.png images/forward_alt.png images/star.png + images/down_alt.png diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index 0ebc74f17..147296b56 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -13,7 +13,7 @@ 0 0 606 - 375 + 387 @@ -83,30 +83,7 @@ - - - - - 0 - 0 - - - - Altitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - meters - - - - + @@ -122,7 +99,7 @@ - + @@ -157,16 +134,6 @@ - - - - -5000.000000000000000 - - - 5000.000000000000000 - - - @@ -197,28 +164,28 @@ - + 999999999 - + meters - + degrees - + Bearing @@ -228,14 +195,14 @@ - + 360.000000000000000 - + @@ -285,7 +252,7 @@ - + Velocity @@ -295,9 +262,62 @@ - + + + + + + 0 + 0 + + + + Altitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + -5000.000000000000000 + + + 5000.000000000000000 + + + + + + + meters + + + + + + + Relative altitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + meters + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8a8f0429d..3e7be12c6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -161,6 +161,8 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) m_map->Home->SetShowSafeArea(true); // show the safe area + if(m_map->Home) + connect(m_map->Home,SIGNAL(homedoubleclick(HomeItem*)),this,SLOT(onHomeDoubleClick(HomeItem*))); m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters @@ -213,39 +215,16 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - qDebug()<<"here0"; model=new flightDataModel(this); - qDebug()<<"here1"; table=new pathPlanner(); - qDebug()<<"here2"; selectionModel=new QItemSelectionModel(model); - qDebug()<<"here3"; - proxy=new modelMapProxy(this,m_map,model,selectionModel); - qDebug()<<"here4"; + mapProxy=new modelMapProxy(this,m_map,model,selectionModel); table->setModel(model,selectionModel); - qDebug()<<"here5"; - table->show(); - qDebug()<<"here6"; waypoint_edit_dialog=new opmap_edit_waypoint_dialog(NULL,model,selectionModel); - qDebug()<<"here7"; + UAVProxy=new modelUavoProxy(this,model); + connect(table,SIGNAL(sendPathPlanToUAV()),UAVProxy,SLOT(modelToObjects())); + connect(table,SIGNAL(receivePathPlanFromUAV()),UAVProxy,SLOT(objectsToModel())); -/* - distBearing db; - db.distance=100; - db.bearing=0; - WayPointItem * p1=m_map->WPCreate(db,10,"aaa"); - - db.distance=100; - db.bearing=45; - WayPointItem * p2=m_map->WPCreate(db,10,"bbb"); - m_map->WPCircleCreate(p2,p1,true); - t_waypoint *wp = new t_waypoint; - wp->map_wp_item=p1; - m_waypoint_list.append(wp); - wp=new t_waypoint; - wp->map_wp_item=p2; - m_waypoint_list.append(wp); -*/ magicWayPoint=m_map->magicWPCreate(); magicWayPoint->setVisible(false); @@ -310,6 +289,18 @@ OPMapGadgetWidget::~OPMapGadgetWidget() delete m_map; m_map = NULL; } + if(model) + delete model; + if(table) + delete table; + if(selectionModel) + delete selectionModel; + if(mapProxy) + delete mapProxy; + if(waypoint_edit_dialog) + delete waypoint_edit_dialog; + if(UAVProxy) + delete UAVProxy; } // ************************************************************************************* @@ -530,6 +521,12 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) // **************** } +void OPMapGadgetWidget::closeEvent(QCloseEvent *event) +{ + table->close(); + QWidget::closeEvent(event); +} + // ************************************************************************************* // timer signals @@ -1295,7 +1292,6 @@ void OPMapGadgetWidget::createActions() wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); wayPointEditorAct->setShortcut(tr("Ctrl+W")); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); - wayPointEditorAct->setEnabled(true); // temporary connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); addWayPointActFromContextMenu = new QAction(tr("&Add waypoint"), this); @@ -1702,7 +1698,7 @@ void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) void OPMapGadgetWidget::onOpenWayPointEditorAct_triggered() { - //TODO + table->show(); } void OPMapGadgetWidget::onAddWayPointAct_triggeredFromContextMenu() { @@ -1722,7 +1718,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) return; // m_map->WPCreate(coord, 0, ""); - proxy->createWayPoint(coord); + mapProxy->createWayPoint(coord); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); @@ -1748,7 +1744,6 @@ void OPMapGadgetWidget::onEditWayPointAct_triggered() return; waypoint_edit_dialog->editWaypoint(m_mouse_waypoint); - m_mouse_waypoint = NULL; } @@ -1788,7 +1783,7 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() if (!m_mouse_waypoint) return; - proxy->deleteWayPoint(m_mouse_waypoint->Number()); + mapProxy->deleteWayPoint(m_mouse_waypoint->Number()); } void OPMapGadgetWidget::onClearWayPointsAct_triggered() @@ -1799,7 +1794,7 @@ void OPMapGadgetWidget::onClearWayPointsAct_triggered() if (m_map_mode != Normal_MapMode) return; - proxy->deleteAll(); + mapProxy->deleteAll(); } @@ -2117,3 +2112,8 @@ void OPMapGadgetWidget::on_tbFind_clicked() m_widget->leFind->setPalette(pal); } } + +void OPMapGadgetWidget::onHomeDoubleClick(HomeItem *) +{ + new homeEditor(m_map->Home,this); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 0b60f4931..602461eb2 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -34,6 +34,7 @@ #include "flightdatamodel.h" #include "pathplanner.h" #include "modelmapproxy.h" +#include "modeluavoproxy.h" #include #include @@ -59,6 +60,8 @@ #include #include "opmap_edit_waypoint_dialog.h" +#include "homeeditor.h" + // ****************************************************** namespace Ui @@ -124,6 +127,7 @@ protected: void resizeEvent(QResizeEvent *event); void mouseMoveEvent(QMouseEvent *event); void contextMenuEvent(QContextMenuEvent *event); + void closeEvent(QCloseEvent *); private slots: void wpDoubleClickEvent(WayPointItem *wp); void updatePosition(); @@ -202,7 +206,7 @@ private slots: void onMaxUpdateRateActGroup_triggered(QAction *action); void onChangeDefaultLocalAndZoom(); void on_tbFind_clicked(); - + void onHomeDoubleClick(HomeItem*); private: // ***** @@ -244,6 +248,10 @@ private: mapcontrol::WayPointItem *m_mouse_waypoint; + modelUavoProxy * UAVProxy; + + + QMutex m_map_mutex; bool m_telemetry_connected; @@ -334,7 +342,7 @@ private: flightDataModel * model; pathPlanner * table; - modelMapProxy * proxy; + modelMapProxy * mapProxy; QItemSelectionModel * selectionModel; }; From ecbf02fd3384229d38e14644ec6cf84f438505cd Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 25 Jun 2012 19:41:59 +0100 Subject: [PATCH 033/116] GCS/OPMap-Added missing header information. Did some cleaning --- .../src/plugins/opmap/flightdatamodel.cpp | 31 ++++- .../src/plugins/opmap/flightdatamodel.h | 31 ++++- .../src/plugins/opmap/homeeditor.cpp | 26 ++++ .../src/plugins/opmap/homeeditor.h | 26 ++++ .../src/plugins/opmap/modelmapproxy.cpp | 39 ++---- .../src/plugins/opmap/modelmapproxy.h | 29 +++- .../src/plugins/opmap/modeluavoproxy.cpp | 51 +++---- .../src/plugins/opmap/modeluavoproxy.h | 26 ++++ .../opmap/opmap_edit_waypoint_dialog.cpp | 127 +++++++----------- .../opmap/opmap_edit_waypoint_dialog.h | 7 +- .../src/plugins/opmap/opmapgadget.h | 1 - .../src/plugins/opmap/opmapgadgetwidget.cpp | 32 +---- .../src/plugins/opmap/opmapgadgetwidget.h | 46 +------ .../src/plugins/opmap/pathplanner.cpp | 32 ++++- .../src/plugins/opmap/pathplanner.h | 37 ++++- .../src/plugins/opmap/pathplanner.ui | 4 +- .../src/plugins/opmap/widgetdelegates.cpp | 64 +++++---- .../src/plugins/opmap/widgetdelegates.h | 32 ++++- 18 files changed, 388 insertions(+), 253 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index 9740c50d0..7d84a6839 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -1,3 +1,30 @@ +/** + ****************************************************************************** + * + * @file flightdatamodel.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #include "flightdatamodel.h" #include #include @@ -517,7 +544,6 @@ void flightDataModel::readFromFile(QString fileName) removeRows(0,rowCount()); QFile file(fileName); QDomDocument doc("PathPlan"); - qDebug()<<"FILE OPEN"<altitude=field.attribute("value").toDouble(); else if(field.attribute("name")=="description") @@ -602,7 +626,6 @@ void flightDataModel::readFromFile(QString fileName) } fieldNode=fieldNode.nextSibling(); - qDebug()<<"field node is null"< @@ -51,11 +77,6 @@ private: QList dataStorage; QVariant getColumnByIndex(const pathPlanData *row, const int index) const; bool setColumnByIndex(pathPlanData *row, const int index, const QVariant value); -signals: - //void dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); - - - }; #endif // FLIGHTDATAMODEL_H diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp index 6c0ace86a..9c2d9dc9d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp @@ -1,3 +1,29 @@ +/** + ****************************************************************************** + * + * @file homeeditor.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include "homeeditor.h" #include "ui_homeeditor.h" diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.h b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h index 69a905edd..e0214c207 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.h +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h @@ -1,3 +1,29 @@ +/** + ****************************************************************************** + * + * @file homeeditor.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef HOMEEDITOR_H #define HOMEEDITOR_H diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index 48d78a34c..478f0b680 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file pathplanmanager.cpp + * @file modelmapproxy.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ @@ -37,15 +37,6 @@ modelMapProxy::modelMapProxy(QObject *parent,OPMapWidget *map,flightDataModel * connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(on_WPValuesChanged(WayPointItem*))); } -void modelMapProxy::on_WPDeleted(int wp_numberint,WayPointItem * wp) -{ -} - -void modelMapProxy::on_WPInserted(int wp_number, WayPointItem * wp) -{ - -} - void modelMapProxy::on_WPValuesChanged(WayPointItem * wp) { QModelIndex index; @@ -87,18 +78,18 @@ modelMapProxy::overlayType modelMapProxy::overlayTranslate(int type) { switch(type) { - case ComboBoxDelegate::MODE_FLYENDPOINT: - case ComboBoxDelegate::MODE_FLYVECTOR: - case ComboBoxDelegate::MODE_DRIVEENDPOINT: - case ComboBoxDelegate::MODE_DRIVEVECTOR: + case mapDataDelegate::MODE_FLYENDPOINT: + case mapDataDelegate::MODE_FLYVECTOR: + case mapDataDelegate::MODE_DRIVEENDPOINT: + case mapDataDelegate::MODE_DRIVEVECTOR: return OVERLAY_LINE; break; - case ComboBoxDelegate::MODE_FLYCIRCLERIGHT: - case ComboBoxDelegate::MODE_DRIVECIRCLERIGHT: + case mapDataDelegate::MODE_FLYCIRCLERIGHT: + case mapDataDelegate::MODE_DRIVECIRCLERIGHT: return OVERLAY_CIRCLE_RIGHT; break; - case ComboBoxDelegate::MODE_FLYCIRCLELEFT: - case ComboBoxDelegate::MODE_DRIVECIRCLELEFT: + case mapDataDelegate::MODE_FLYCIRCLELEFT: + case mapDataDelegate::MODE_DRIVECIRCLELEFT: return OVERLAY_CIRCLE_LEFT; break; default: @@ -172,23 +163,23 @@ void modelMapProxy::refreshOverlays() createOverlay(wp_current,findWayPointNumber(wp_error),wp_error_overlay,Qt::red); switch(model->data(model->index(x,flightDataModel::COMMAND)).toInt()) { - case ComboBoxDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: + case mapDataDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); break; - case ComboBoxDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: + case mapDataDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); break; - case ComboBoxDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: + case mapDataDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::yellow); break; - case ComboBoxDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: + case mapDataDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::yellow); break; - case ComboBoxDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: + case mapDataDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); wp_next=findWayPointNumber(x+1); @@ -207,8 +198,6 @@ WayPointItem * modelMapProxy::findWayPointNumber(int number) void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int last) { - qDebug()<<"modelMapProxy::on_rowsRemoved"<<"first"<first-1;x--) { myMap->WPDelete(x); diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h index c6bcaf076..31640f8bb 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h @@ -1,3 +1,29 @@ +/** + ****************************************************************************** + * + * @file modelmapproxy.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef MODELMAPPROXY_H #define MODELMAPPROXY_H #include @@ -26,9 +52,6 @@ private slots: void on_dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); void on_rowsInserted ( const QModelIndex & parent, int first, int last ); void on_rowsRemoved ( const QModelIndex & parent, int first, int last ); - - void on_WPDeleted(int wp_numberint, WayPointItem *); - void on_WPInserted(int,WayPointItem*); void on_WPValuesChanged(WayPointItem *wp); void on_currentRowChanged(QModelIndex,QModelIndex); void on_selectedWPChanged(QList); diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp index e8b07bb23..16ba0a040 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -1,3 +1,29 @@ +/** + ****************************************************************************** + * + * @file modeluavproxy.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include "modeluavoproxy.h" #include "extensionsystem/pluginmanager.h" #include @@ -11,32 +37,7 @@ modelUavoProxy::modelUavoProxy(QObject *parent,flightDataModel * model):QObject( Q_ASSERT(waypointObj != NULL); pathactionObj=PathAction::GetInstance(objManager); Q_ASSERT(pathactionObj != NULL); - - /* - int instances=objManager->getNumInstances(pathactionObj->getObjID()); - PathAction * actionObj=new PathAction; - actionObj->initialize(instances,actionObj->getMetaObject()); - objManager->registerObject(actionObj); - actionObj->updated(); - - instances=objManager->getNumInstances(pathactionObj->getObjID()); - actionObj=new PathAction; - actionObj->initialize(instances,actionObj->getMetaObject()); - objManager->registerObject(actionObj); - actionObj->updated(); - - instances=objManager->getNumInstances(pathactionObj->getObjID()); - actionObj=new PathAction; - actionObj->initialize(instances,actionObj->getMetaObject()); - objManager->registerObject(actionObj); - actionObj->updated(); - */ } -/*WPDESCRITPTION,LATPOSITION,LNGPOSITION,DISRELATIVE,BEARELATIVE,ISRELATIVE,ALTITUDE, - VELOCITY,MODE,MODE_PARAMS0,MODE_PARAMS1,MODE_PARAMS2,MODE_PARAMS3, - CONDITION,CONDITION_PARAMS0,CONDITION_PARAMS1,CONDITION_PARAMS2,CONDITION_PARAMS3, - COMMAND,JUMPDESTINATION,ERRORDESTINATION,LOCKED - */ void modelUavoProxy::modelToObjects() { PathAction * act=NULL; diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h index 266cfbf89..42d020628 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h @@ -1,3 +1,29 @@ +/** + ****************************************************************************** + * + * @file modeluavproxy.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #ifndef MODELUAVOPROXY_H #define MODELUAVOPROXY_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 3182e2cd8..8f3123b21 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -42,43 +42,39 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract connect(ui->cbMode,SIGNAL(currentIndexChanged(int)),this,SLOT(setupModeWidgets())); connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets())); - ComboBoxDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); - ComboBoxDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); - ComboBoxDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); - - // VELOCITY, - + mapDataDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); + mapDataDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); + mapDataDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); mapper = new QDataWidgetMapper(this); - mapper->setItemDelegate(new ComboBoxDelegate(this)); + mapper->setItemDelegate(new mapDataDelegate(this)); connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(on_currentIndexChanged(int))); - mapper->setModel(model); - //mapper->addMapping(ui->spinBoxNumber, - mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED); - mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION); - mapper->addMapping(ui->doubleSpinBoxLongitude,flightDataModel::LNGPOSITION); - mapper->addMapping(ui->doubleSpinBoxAltitude,flightDataModel::ALTITUDE); - mapper->addMapping(ui->lineEditDescription,flightDataModel::WPDESCRITPTION); - mapper->addMapping(ui->checkBoxRelative,flightDataModel::ISRELATIVE); - mapper->addMapping(ui->doubleSpinBoxBearing,flightDataModel::BEARELATIVE); - mapper->addMapping(ui->doubleSpinBoxVelocity,flightDataModel::VELOCITY); - mapper->addMapping(ui->spinBoxDistance,flightDataModel::DISRELATIVE); - mapper->addMapping(ui->cbMode,flightDataModel::MODE); - mapper->addMapping(ui->dsb_modeParam1,flightDataModel::MODE_PARAMS0); - mapper->addMapping(ui->dsb_modeParam2,flightDataModel::MODE_PARAMS1); - mapper->addMapping(ui->dsb_modeParam3,flightDataModel::MODE_PARAMS2); - mapper->addMapping(ui->dsb_modeParam4,flightDataModel::MODE_PARAMS3); + mapper->setModel(model); + mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED); + mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION); + mapper->addMapping(ui->doubleSpinBoxLongitude,flightDataModel::LNGPOSITION); + mapper->addMapping(ui->doubleSpinBoxAltitude,flightDataModel::ALTITUDE); + mapper->addMapping(ui->lineEditDescription,flightDataModel::WPDESCRITPTION); + mapper->addMapping(ui->checkBoxRelative,flightDataModel::ISRELATIVE); + mapper->addMapping(ui->doubleSpinBoxBearing,flightDataModel::BEARELATIVE); + mapper->addMapping(ui->doubleSpinBoxVelocity,flightDataModel::VELOCITY); + mapper->addMapping(ui->spinBoxDistance,flightDataModel::DISRELATIVE); + mapper->addMapping(ui->cbMode,flightDataModel::MODE); + mapper->addMapping(ui->dsb_modeParam1,flightDataModel::MODE_PARAMS0); + mapper->addMapping(ui->dsb_modeParam2,flightDataModel::MODE_PARAMS1); + mapper->addMapping(ui->dsb_modeParam3,flightDataModel::MODE_PARAMS2); + mapper->addMapping(ui->dsb_modeParam4,flightDataModel::MODE_PARAMS3); - mapper->addMapping(ui->cbCondition,flightDataModel::CONDITION); - mapper->addMapping(ui->dsb_condParam1,flightDataModel::CONDITION_PARAMS0); - mapper->addMapping(ui->dsb_condParam2,flightDataModel::CONDITION_PARAMS1); - mapper->addMapping(ui->dsb_condParam3,flightDataModel::CONDITION_PARAMS2); - mapper->addMapping(ui->dsb_condParam4,flightDataModel::CONDITION_PARAMS0); + mapper->addMapping(ui->cbCondition,flightDataModel::CONDITION); + mapper->addMapping(ui->dsb_condParam1,flightDataModel::CONDITION_PARAMS0); + mapper->addMapping(ui->dsb_condParam2,flightDataModel::CONDITION_PARAMS1); + mapper->addMapping(ui->dsb_condParam3,flightDataModel::CONDITION_PARAMS2); + mapper->addMapping(ui->dsb_condParam4,flightDataModel::CONDITION_PARAMS0); - mapper->addMapping(ui->cbCommand,flightDataModel::COMMAND); - mapper->addMapping(ui->sbJump,flightDataModel::JUMPDESTINATION); - mapper->addMapping(ui->sbError,flightDataModel::ERRORDESTINATION); - connect(itemSelection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(on_currentRowChanged(QModelIndex,QModelIndex))); + mapper->addMapping(ui->cbCommand,flightDataModel::COMMAND); + mapper->addMapping(ui->sbJump,flightDataModel::JUMPDESTINATION); + mapper->addMapping(ui->sbError,flightDataModel::ERRORDESTINATION); + connect(itemSelection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(on_currentRowChanged(QModelIndex,QModelIndex))); } void opmap_edit_waypoint_dialog::on_currentIndexChanged(int index) { @@ -90,44 +86,31 @@ void opmap_edit_waypoint_dialog::on_currentIndexChanged(int index) itemSelection->setCurrentIndex(idx,QItemSelectionModel::Select | QItemSelectionModel::Rows); } -// destrutor opmap_edit_waypoint_dialog::~opmap_edit_waypoint_dialog() { delete ui; } -// ********************************************************************* - void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() { close(); } -void opmap_edit_waypoint_dialog::on_pushButtonApply_clicked() -{ - -} - -void opmap_edit_waypoint_dialog::on_pushButtonRevert_clicked() -{ - -} - void opmap_edit_waypoint_dialog::setupModeWidgets() { - ComboBoxDelegate::ModeOptions mode=(ComboBoxDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + mapDataDelegate::ModeOptions mode=(mapDataDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); switch(mode) { - case ComboBoxDelegate::MODE_FLYENDPOINT: - case ComboBoxDelegate::MODE_FLYVECTOR: - case ComboBoxDelegate::MODE_FLYCIRCLERIGHT: - case ComboBoxDelegate::MODE_FLYCIRCLELEFT: - case ComboBoxDelegate::MODE_DRIVEENDPOINT: - case ComboBoxDelegate::MODE_DRIVEVECTOR: - case ComboBoxDelegate::MODE_DRIVECIRCLELEFT: - case ComboBoxDelegate::MODE_DRIVECIRCLERIGHT: - case ComboBoxDelegate::MODE_DISARMALARM: + case mapDataDelegate::MODE_FLYENDPOINT: + case mapDataDelegate::MODE_FLYVECTOR: + case mapDataDelegate::MODE_FLYCIRCLERIGHT: + case mapDataDelegate::MODE_FLYCIRCLELEFT: + case mapDataDelegate::MODE_DRIVEENDPOINT: + case mapDataDelegate::MODE_DRIVEVECTOR: + case mapDataDelegate::MODE_DRIVECIRCLELEFT: + case mapDataDelegate::MODE_DRIVECIRCLERIGHT: + case mapDataDelegate::MODE_DISARMALARM: ui->modeParam1->setVisible(false); ui->modeParam2->setVisible(false); ui->modeParam3->setVisible(false); @@ -137,7 +120,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(false); ui->dsb_modeParam4->setVisible(false); break; - case ComboBoxDelegate::MODE_FIXEDATTITUDE: + case mapDataDelegate::MODE_FIXEDATTITUDE: ui->modeParam1->setText("pitch"); ui->modeParam2->setText("roll"); ui->modeParam3->setText("yaw"); @@ -151,7 +134,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(true); ui->dsb_modeParam4->setVisible(true); break; - case ComboBoxDelegate::MODE_SETACCESSORY: + case mapDataDelegate::MODE_SETACCESSORY: ui->modeParam1->setText("Acc.channel"); ui->modeParam2->setText("Value"); ui->modeParam1->setVisible(true); @@ -167,12 +150,12 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() } void opmap_edit_waypoint_dialog::setupConditionWidgets() { - ComboBoxDelegate::EndConditionOptions mode=(ComboBoxDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + mapDataDelegate::EndConditionOptions mode=(mapDataDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); switch(mode) { - case ComboBoxDelegate::ENDCONDITION_NONE: - case ComboBoxDelegate::ENDCONDITION_IMMEDIATE: - case ComboBoxDelegate::ENDCONDITION_PYTHONSCRIPT: + case mapDataDelegate::ENDCONDITION_NONE: + case mapDataDelegate::ENDCONDITION_IMMEDIATE: + case mapDataDelegate::ENDCONDITION_PYTHONSCRIPT: ui->condParam1->setVisible(false); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -182,7 +165,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam3->setVisible(false); ui->dsb_condParam4->setVisible(false); break; - case ComboBoxDelegate::ENDCONDITION_TIMEOUT: + case mapDataDelegate::ENDCONDITION_TIMEOUT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -193,7 +176,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Timeout(ms)"); break; - case ComboBoxDelegate::ENDCONDITION_DISTANCETOTARGET: + case mapDataDelegate::ENDCONDITION_DISTANCETOTARGET: ui->condParam1->setVisible(true); ui->condParam2->setVisible(true); ui->condParam3->setVisible(false); @@ -205,7 +188,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->condParam1->setText("Distance(m)"); ui->condParam2->setText("Flag(0=2D,1=3D)");//FIXME break; - case ComboBoxDelegate::ENDCONDITION_LEGREMAINING: + case mapDataDelegate::ENDCONDITION_LEGREMAINING: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -216,7 +199,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); break; - case ComboBoxDelegate::ENDCONDITION_ABOVEALTITUDE: + case mapDataDelegate::ENDCONDITION_ABOVEALTITUDE: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -227,7 +210,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Altitude in meters (negative)"); break; - case ComboBoxDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: + case mapDataDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -249,16 +232,6 @@ void opmap_edit_waypoint_dialog::on_pushButtonCancel_clicked() close(); } -int opmap_edit_waypoint_dialog::saveSettings() -{ - -} - -void opmap_edit_waypoint_dialog::loadFromWP(mapcontrol::WayPointItem *waypoint_item) -{ - -} - void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) return; @@ -266,8 +239,6 @@ void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint mapper->setCurrentIndex(waypoint_item->Number()); } -// ********************************************************************* - void opmap_edit_waypoint_dialog::on_pushButton_clicked() { mapper->toPrevious(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 6fa87e7ef..6cd227c26 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file opmap_edit_waypoint_dialog.cpp + * @file opmap_edit_waypoint_dialog.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ @@ -51,12 +51,9 @@ public: */ void editWaypoint(mapcontrol::WayPointItem *waypoint_item); - void loadFromWP(mapcontrol::WayPointItem *waypoint_item); - private: Ui::opmap_edit_waypoint_dialog *ui; mapcontrol::WayPointItem * my_waypoint; - int saveSettings(); QDataWidgetMapper *mapper; QAbstractItemModel * model; QItemSelectionModel * itemSelection; @@ -68,8 +65,6 @@ private slots: void setupPositionWidgets(bool isRelative); void setupConditionWidgets(); void on_pushButtonCancel_clicked(); - void on_pushButtonRevert_clicked(); - void on_pushButtonApply_clicked(); void on_pushButtonOK_clicked(); void on_pushButton_clicked(); void on_pushButton_2_clicked(); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h index 87866c43f..eb69255fa 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h @@ -33,7 +33,6 @@ #include "opmapgadgetconfiguration.h" class IUAVGadget; -//class QList; class QWidget; class QString; class OPMapGadgetWidget; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 3e7be12c6..ed2ecdf10 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -289,17 +289,17 @@ OPMapGadgetWidget::~OPMapGadgetWidget() delete m_map; m_map = NULL; } - if(model) + if(!model.isNull()) delete model; - if(table) + if(!table.isNull()) delete table; - if(selectionModel) + if(!selectionModel.isNull()) delete selectionModel; - if(mapProxy) + if(!mapProxy.isNull()) delete mapProxy; - if(waypoint_edit_dialog) + if(!waypoint_edit_dialog.isNull()) delete waypoint_edit_dialog; - if(UAVProxy) + if(!UAVProxy.isNull()) delete UAVProxy; } @@ -625,9 +625,6 @@ void OPMapGadgetWidget::updateMousePos() // find out if we are over the home position mapcontrol::HomeItem *home = qgraphicsitem_cast(item); - // find out if we are over the UAV - mapcontrol::UAVItem *uav = qgraphicsitem_cast(item); - // find out if we have a waypoint under the mouse cursor mapcontrol::WayPointItem *wp = qgraphicsitem_cast(item); @@ -658,19 +655,6 @@ void OPMapGadgetWidget::updateMousePos() s += " " + QString::number(dist * 1000, 'f', 1) + "m"; s += " " + QString::number(bear, 'f', 1) + "deg"; } - else - if (uav) - { - s += " uav"; - - double latitude; - double longitude; - double altitude; - if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position - { - internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); - } - } m_widget->labelMousePos->setText(s); } @@ -1459,10 +1443,6 @@ void OPMapGadgetWidget::createActions() uavTrailDistance_act->setData(uav_trail_distance); uavTrailDistanceAct.append(uavTrailDistance_act); } - - // ***** - - // *********************** } void OPMapGadgetWidget::onReloadAct_triggered() diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 602461eb2..b7ab82909 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -208,58 +208,30 @@ private slots: void on_tbFind_clicked(); void onHomeDoubleClick(HomeItem*); private: - - // ***** - int m_min_zoom; int m_max_zoom; - double m_heading; // uav heading - internals::PointLatLng m_mouse_lat_lon; internals::PointLatLng m_context_menu_lat_lon; - int m_prev_tile_number; - opMapModeType m_map_mode; - int m_maxUpdateRate; - t_home m_home_position; - QStringList findPlaceWordList; QCompleter *findPlaceCompleter; - QTimer *m_updateTimer; QTimer *m_statusUpdateTimer; - Ui::OPMap_Widget *m_widget; - mapcontrol::OPMapWidget *m_map; - ExtensionSystem::PluginManager *pm; UAVObjectManager *obm; UAVObjectUtilManager *obum; - - - opmap_edit_waypoint_dialog * waypoint_edit_dialog; - + QPointer waypoint_edit_dialog; QStandardItemModel wayPoint_treeView_model; - mapcontrol::WayPointItem *m_mouse_waypoint; - - modelUavoProxy * UAVProxy; - - - + QPointer UAVProxy; QMutex m_map_mutex; - bool m_telemetry_connected; - - // ***** - - void createActions(); - QAction *closeAct1; QAction *closeAct2; QAction *reloadAct; @@ -314,15 +286,11 @@ private: QActionGroup *maxUpdateRateActGroup; QList maxUpdateRateAct; - // ***** - + void createActions(); void homeMagicWaypoint(); - void moveToMagicWaypointPosition(); - void hideMagicWaypointControls(); void showMagicWaypointControls(); - void keepMagicWaypointWithInSafeArea(); double distance(internals::PointLatLng from, internals::PointLatLng to); @@ -340,10 +308,10 @@ private: internals::PointLatLng lastLatLngMouse; WayPointItem * magicWayPoint; - flightDataModel * model; - pathPlanner * table; - modelMapProxy * mapProxy; - QItemSelectionModel * selectionModel; + QPointer model; + QPointer table; + QPointer mapProxy; + QPointer selectionModel; }; #endif /* OPMAP_GADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp index 65f14b3cb..78137fd7e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -1,3 +1,30 @@ +/** + ****************************************************************************** + * + * @file pathplanner.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #include "pathplanner.h" #include "ui_pathplanner.h" #include "widgetdelegates.h" @@ -6,7 +33,7 @@ pathPlanner::pathPlanner(QWidget *parent) : QWidget(parent), - ui(new Ui::testTable),wid(NULL),myModel(NULL) + ui(new Ui::pathPlannerUI),wid(NULL),myModel(NULL) { ui->setupUi(this); } @@ -23,7 +50,7 @@ void pathPlanner::setModel(flightDataModel *model,QItemSelectionModel *selection ui->tableView->setModel(model); ui->tableView->setSelectionModel(selection); ui->tableView->setSelectionBehavior(QAbstractItemView::SelectRows); - ui->tableView->setItemDelegate(new ComboBoxDelegate(this)); + ui->tableView->setItemDelegate(new mapDataDelegate(this)); connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(on_rowsInserted(const QModelIndex&,int,int))); wid=new opmap_edit_waypoint_dialog(NULL,model,selection); ui->tableView->resizeColumnsToContents(); @@ -82,7 +109,6 @@ void pathPlanner::on_groupBox_clicked() void pathPlanner::on_groupBox_toggled(bool arg1) { - // wid->close(); wid->setVisible(arg1); } diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h index 2b7d270c7..184a68d1b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h @@ -1,11 +1,38 @@ -#ifndef TESTTABLE_H -#define TESTTABLE_H +/** + ****************************************************************************** + * + * @file pathplanner.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PATHPLANNER_H +#define PATHPLANNER_H #include #include "flightdatamodel.h" #include "opmap_edit_waypoint_dialog.h" namespace Ui { -class testTable; +class pathPlannerUI; } class pathPlanner : public QWidget @@ -41,7 +68,7 @@ private slots: void on_tbFetchFromUAV_clicked(); private: - Ui::testTable *ui; + Ui::pathPlannerUI *ui; opmap_edit_waypoint_dialog * wid; flightDataModel * myModel; signals: @@ -49,4 +76,4 @@ signals: void receivePathPlanFromUAV(); }; -#endif // TESTTABLE_H +#endif // PATHPLANNER_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui index e5cfd5488..fbb59a4e3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.ui @@ -1,7 +1,7 @@ - testTable - + pathPlannerUI + 0 diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp index 0a7517928..d2297856d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -1,8 +1,34 @@ +/** + ****************************************************************************** + * + * @file widgetdelegates.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ #include "widgetdelegates.h" #include #include #include -QWidget *ComboBoxDelegate::createEditor(QWidget *parent, +QWidget *mapDataDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem & option, const QModelIndex & index) const { @@ -12,18 +38,18 @@ QWidget *ComboBoxDelegate::createEditor(QWidget *parent, { case flightDataModel::MODE: box=new QComboBox(parent); - ComboBoxDelegate::loadComboBox(box,flightDataModel::MODE); + mapDataDelegate::loadComboBox(box,flightDataModel::MODE); return box; break; case flightDataModel::CONDITION: box=new QComboBox(parent); - ComboBoxDelegate::loadComboBox(box,flightDataModel::CONDITION); + mapDataDelegate::loadComboBox(box,flightDataModel::CONDITION); return box; break; case flightDataModel::COMMAND: box=new QComboBox(parent); - ComboBoxDelegate::loadComboBox(box,flightDataModel::COMMAND); + mapDataDelegate::loadComboBox(box,flightDataModel::COMMAND); return box; break; default: @@ -35,7 +61,7 @@ QWidget *ComboBoxDelegate::createEditor(QWidget *parent, return editor; } -void ComboBoxDelegate::setEditorData(QWidget *editor, +void mapDataDelegate::setEditorData(QWidget *editor, const QModelIndex &index) const { QString className=editor->metaObject()->className(); @@ -46,16 +72,11 @@ void ComboBoxDelegate::setEditorData(QWidget *editor, qDebug()<<"VALUE="<setCurrentIndex(x); } - /* else if (className.contains("QRadioButton")) { - bool value = index.model()->data(index, Qt::EditRole).toBool(); - QRadioButton *radioButton = static_cast(editor); - radioButton->setChecked(value); - }*/ else QItemDelegate::setEditorData(editor, index); } -void ComboBoxDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, +void mapDataDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const { QString className=editor->metaObject()->className(); @@ -63,23 +84,18 @@ void ComboBoxDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, QComboBox *comboBox = static_cast(editor); int value = comboBox->itemData(comboBox->currentIndex()).toInt(); model->setData(index, value, Qt::EditRole); - }/* - else if (className.contains("QRadioButton")) { - QRadioButton *radioButton = static_cast(editor); - bool value = radioButton->isChecked(); - model->setData(index, value, Qt::EditRole); - }*/ + } else QItemDelegate::setModelData(editor,model,index); } -void ComboBoxDelegate::updateEditorGeometry(QWidget *editor, +void mapDataDelegate::updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &/* index */) const { editor->setGeometry(option.rect); } -void ComboBoxDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDataEnum type) +void mapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDataEnum type) { switch(type) { @@ -119,15 +135,7 @@ void ComboBoxDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanD break; } } -/* -void ComboBoxDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const -{ - QStyleOptionComboBox opt; - opt.rect=option.rect; - QApplication::style()->drawComplexControl(QStyle::CC_ComboBox, &opt, - painter,createEditor(this,option,index)); -}*/ -ComboBoxDelegate::ComboBoxDelegate(QObject *parent):QItemDelegate(parent) +mapDataDelegate::mapDataDelegate(QObject *parent):QItemDelegate(parent) { } diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h index 7e85ccabf..684d93ee6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h @@ -1,3 +1,30 @@ +/** + ****************************************************************************** + * + * @file widgetdelegates.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + #ifndef WIDGETDELEGATES_H #define WIDGETDELEGATES_H #include @@ -5,7 +32,7 @@ #include "flightdatamodel.h" -class ComboBoxDelegate : public QItemDelegate +class mapDataDelegate : public QItemDelegate { Q_OBJECT @@ -20,7 +47,7 @@ class ComboBoxDelegate : public QItemDelegate COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; - ComboBoxDelegate(QObject *parent = 0); + mapDataDelegate(QObject *parent = 0); QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const; @@ -32,7 +59,6 @@ class ComboBoxDelegate : public QItemDelegate void updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const; static void loadComboBox(QComboBox * combo,flightDataModel::pathPlanDataEnum type); - //void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const; }; #endif // WIDGETDELEGATES_H From 2e97f1ac6af4fb6148b2f639d3d6a5d354401348 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 25 Jun 2012 21:10:40 +0100 Subject: [PATCH 034/116] GCS/OPmap-Changed slot names to get rid of the automatic signal conection failure warning. --- .../plugins/opmap/opmap_edit_waypoint_dialog.cpp | 10 +++++----- .../src/plugins/opmap/opmap_edit_waypoint_dialog.h | 6 +++--- .../openpilotgcs/src/plugins/opmap/pathplanner.cpp | 14 ++------------ .../openpilotgcs/src/plugins/opmap/pathplanner.h | 6 +----- 4 files changed, 11 insertions(+), 25 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 8f3123b21..49014b91b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -48,7 +48,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract mapper = new QDataWidgetMapper(this); mapper->setItemDelegate(new mapDataDelegate(this)); - connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(on_currentIndexChanged(int))); + connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(currentIndexChanged(int))); mapper->setModel(model); mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED); mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION); @@ -74,9 +74,9 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract mapper->addMapping(ui->cbCommand,flightDataModel::COMMAND); mapper->addMapping(ui->sbJump,flightDataModel::JUMPDESTINATION); mapper->addMapping(ui->sbError,flightDataModel::ERRORDESTINATION); - connect(itemSelection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(on_currentRowChanged(QModelIndex,QModelIndex))); + connect(itemSelection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(currentRowChanged(QModelIndex,QModelIndex))); } -void opmap_edit_waypoint_dialog::on_currentIndexChanged(int index) +void opmap_edit_waypoint_dialog::currentIndexChanged(int index) { ui->lbNumber->setText(QString::number(index)); QModelIndex idx=mapper->model()->index(index,0); @@ -226,7 +226,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() break; } } -void opmap_edit_waypoint_dialog::on_pushButtonCancel_clicked() +void opmap_edit_waypoint_dialog::pushButtonCancel_clicked() { my_waypoint = NULL; close(); @@ -272,7 +272,7 @@ void opmap_edit_waypoint_dialog::enableEditWidgets(bool value) } } -void opmap_edit_waypoint_dialog::on_currentRowChanged(QModelIndex current, QModelIndex previous) +void opmap_edit_waypoint_dialog::currentRowChanged(QModelIndex current, QModelIndex previous) { mapper->setCurrentIndex(current.row()); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 6cd227c26..d4be745b8 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -60,16 +60,16 @@ private: private slots: private slots: - void on_currentIndexChanged(int index); + void currentIndexChanged(int index); void setupModeWidgets(); void setupPositionWidgets(bool isRelative); void setupConditionWidgets(); - void on_pushButtonCancel_clicked(); + void pushButtonCancel_clicked(); void on_pushButtonOK_clicked(); void on_pushButton_clicked(); void on_pushButton_2_clicked(); void enableEditWidgets(bool); - void on_currentRowChanged(QModelIndex,QModelIndex); + void currentRowChanged(QModelIndex,QModelIndex); }; #endif // OPMAP_EDIT_WAYPOINT_DIALOG_H diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp index 78137fd7e..532e198c2 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -51,12 +51,12 @@ void pathPlanner::setModel(flightDataModel *model,QItemSelectionModel *selection ui->tableView->setSelectionModel(selection); ui->tableView->setSelectionBehavior(QAbstractItemView::SelectRows); ui->tableView->setItemDelegate(new mapDataDelegate(this)); - connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(on_rowsInserted(const QModelIndex&,int,int))); + connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(rowsInserted(const QModelIndex&,int,int))); wid=new opmap_edit_waypoint_dialog(NULL,model,selection); ui->tableView->resizeColumnsToContents(); } -void pathPlanner::on_rowsInserted ( const QModelIndex & parent, int start, int end ) +void pathPlanner::rowsInserted ( const QModelIndex & parent, int start, int end ) { Q_UNUSED(parent); for(int x=start;xwriteToFile(fileName); } -void pathPlanner::on_groupBox_clicked() -{ - -} - -void pathPlanner::on_groupBox_toggled(bool arg1) -{ - wid->setVisible(arg1); -} - void pathPlanner::on_tbDetails_clicked() { if(wid) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h index 184a68d1b..5f0bfffee 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h @@ -45,7 +45,7 @@ public: void setModel(flightDataModel *model,QItemSelectionModel *selection); private slots: - void on_rowsInserted ( const QModelIndex & parent, int start, int end ); + void rowsInserted ( const QModelIndex & parent, int start, int end ); void on_tbAdd_clicked(); @@ -57,10 +57,6 @@ private slots: void on_tbSaveToFile_clicked(); - void on_groupBox_clicked(); - - void on_groupBox_toggled(bool arg1); - void on_tbDetails_clicked(); void on_tbSendToUAV_clicked(); From 89d7f0adfd85648a32cd5280932068559d49b11f Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 25 Jun 2012 21:11:07 +0100 Subject: [PATCH 035/116] GCS/OPmap-Changed slot names to get rid of the automatic signal conection failure warning. --- .../src/plugins/opmap/modelmapproxy.cpp | 24 +++++++++---------- .../src/plugins/opmap/modelmapproxy.h | 12 +++++----- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index 478f0b680..ef2111770 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -29,15 +29,15 @@ modelMapProxy::modelMapProxy(QObject *parent,OPMapWidget *map,flightDataModel * model,QItemSelectionModel * selectionModel):QObject(parent),myMap(map),model(model),selection(selectionModel) { - connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(on_rowsInserted(const QModelIndex&,int,int))); - connect(model,SIGNAL(rowsRemoved(const QModelIndex&,int,int)),this,SLOT(on_rowsRemoved(const QModelIndex&,int,int))); - connect(selection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(on_currentRowChanged(QModelIndex,QModelIndex))); - connect(model,SIGNAL(dataChanged(QModelIndex,QModelIndex)),this,SLOT(on_dataChanged(QModelIndex,QModelIndex))); - connect(myMap,SIGNAL(selectedWPChanged(QList)),this,SLOT(on_selectedWPChanged(QList))); - connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(on_WPValuesChanged(WayPointItem*))); + connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(rowsInserted(const QModelIndex&,int,int))); + connect(model,SIGNAL(rowsRemoved(const QModelIndex&,int,int)),this,SLOT(rowsRemoved(const QModelIndex&,int,int))); + connect(selection,SIGNAL(currentRowChanged(QModelIndex,QModelIndex)),this,SLOT(currentRowChanged(QModelIndex,QModelIndex))); + connect(model,SIGNAL(dataChanged(QModelIndex,QModelIndex)),this,SLOT(dataChanged(QModelIndex,QModelIndex))); + connect(myMap,SIGNAL(selectedWPChanged(QList)),this,SLOT(selectedWPChanged(QList))); + connect(myMap,SIGNAL(WPValuesChanged(WayPointItem*)),this,SLOT(WPValuesChanged(WayPointItem*))); } -void modelMapProxy::on_WPValuesChanged(WayPointItem * wp) +void modelMapProxy::WPValuesChanged(WayPointItem * wp) { QModelIndex index; index=model->index(wp->Number(),flightDataModel::LATPOSITION); @@ -54,7 +54,7 @@ void modelMapProxy::on_WPValuesChanged(WayPointItem * wp) model->setData(index,wp->getRelativeCoord().altitudeRelative,Qt::EditRole); } -void modelMapProxy::on_currentRowChanged(QModelIndex current, QModelIndex previous) +void modelMapProxy::currentRowChanged(QModelIndex current, QModelIndex previous) { QList list; WayPointItem * wp=findWayPointNumber(current.row()); @@ -64,7 +64,7 @@ void modelMapProxy::on_currentRowChanged(QModelIndex current, QModelIndex previo myMap->setSelectedWP(list); } -void modelMapProxy::on_selectedWPChanged(QList list) +void modelMapProxy::selectedWPChanged(QList list) { selection->clearSelection(); foreach(WayPointItem * wp,list) @@ -196,7 +196,7 @@ WayPointItem * modelMapProxy::findWayPointNumber(int number) return myMap->WPFind(number); } -void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int last) +void modelMapProxy::rowsRemoved(const QModelIndex &parent, int first, int last) { for(int x=last;x>first-1;x--) { @@ -205,7 +205,7 @@ void modelMapProxy::on_rowsRemoved(const QModelIndex &parent, int first, int las refreshOverlays(); } -void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight) +void modelMapProxy::dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight) { WayPointItem * item=findWayPointNumber(topLeft.row()); if(!item) @@ -281,7 +281,7 @@ void modelMapProxy::on_dataChanged(const QModelIndex &topLeft, const QModelIndex } } -void modelMapProxy::on_rowsInserted(const QModelIndex &parent, int first, int last) +void modelMapProxy::rowsInserted(const QModelIndex &parent, int first, int last) { Q_UNUSED(parent); for(int x=first;x); + void dataChanged ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); + void rowsInserted ( const QModelIndex & parent, int first, int last ); + void rowsRemoved ( const QModelIndex & parent, int first, int last ); + void WPValuesChanged(WayPointItem *wp); + void currentRowChanged(QModelIndex,QModelIndex); + void selectedWPChanged(QList); private: overlayType overlayTranslate(int type); void createOverlay(WayPointItem * from,WayPointItem * to,overlayType type,QColor color); From 2074889c9dec3c76934a8d8c65adcbfe88978dd0 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 26 Jun 2012 20:22:55 +0100 Subject: [PATCH 036/116] GCS/OPMap-Clean commented out code. Delete some qDebugs --- .../libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 3 --- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 4 ---- .../libs/opmapcontrol/src/mapwidget/waypointcircle.cpp | 2 -- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 9 +-------- 4 files changed, 1 insertion(+), 17 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index a4904f6e1..2f07898d0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -392,7 +392,6 @@ namespace mapcontrol found = true; { painter->drawPixmap(core->tileRect.X(),core->tileRect.Y(), core->tileRect.Width(), core->tileRect.Height(),PureImageProxy::FromStream(img)); - // qDebug()<<"tile:"<tileRect.X()<tileRect.Y(); } } } @@ -406,7 +405,6 @@ namespace mapcontrol painter->setFont(config->MissingDataFont); painter->setPen(Qt::red); painter->drawText(QRectF(core->tileRect.X(), core->tileRect.Y(), core->tileRect.Width(), core->tileRect.Height()),Qt::AlignCenter,(core->GettilePoint() == core->GetcenterTileXYLocation()? "CENTER: " :"TILE: ")+core->GettilePoint().ToString()); - //qDebug()<<"ShowTileGridLine:"<GettilePoint().ToString()<<"=="<GetcenterTileXYLocation().ToString(); } } @@ -513,7 +511,6 @@ namespace mapcontrol float scaleValue = zoomDigi+remainder + 1; { MapRenderTransform = scaleValue; - // qDebug()<<"scale="<MaxZoom()) integer=MaxZoom(); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 37dd4e345..bb18ab3f5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -31,11 +31,7 @@ namespace mapcontrol UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) ,autosetdistance(100) { - //QDir dir(":/uavs/images/"); - //QStringList list=dir.entryList(); pic.load(uavPic); - // Don't scale but trust the image we are given - // pic=pic.scaled(50,33,Qt::IgnoreAspectRatio); this->setFlag(QGraphicsItem::ItemIsMovable,true); this->setFlag(QGraphicsItem::ItemIsSelectable,true); localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index f6c5e23b6..aa66bb45d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -34,7 +34,6 @@ namespace mapcontrol WayPointCircle::WayPointCircle(WayPointItem *center, WayPointItem *radius,bool clockwise, MapGraphicItem *map,QColor color):my_center(center), my_radius(radius),my_map(map),QGraphicsEllipseItem(map),myColor(color),myClockWise(clockwise) { - qDebug()<<"circle clock:"<WPType()==relative) - // return; if(Coord()==value) return; - qDebug()<<"SET ABSOLUTE1"; bool abs_coord=false; bool rel_coord=false; if(coord!=value) abs_coord=true; coord=value; distBearingAltitude back=relativeCoord; - qDebug()<<"SET COORD"<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); if(back.distance!=relativeCoord.distance||back.bearing!=relativeCoord.bearing) From 96a8ff3a34c8616a8962204241b4599ebacca961 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 26 Jun 2012 20:47:14 +0100 Subject: [PATCH 037/116] GCS/OPMap-Added relative altitude info to waypoint tooltip. --- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index a9d6e2de4..ceece322e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -451,8 +451,9 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); + QString relativeAltitude_str="Relative altitude:"+QString::number(relativeCoord.altitudeRelative); if(Number()!=-1) - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nAltitude:%6\nType:%7\n%8").arg(QString::number(Number())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(Number())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); else setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); } From 6a85da9b4693ea49ee7bfc359a0debbc26499056 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 27 Jun 2012 00:25:40 +0100 Subject: [PATCH 038/116] GCS/OPMap-Fixes relative altitude refresh issue. --- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 9 +++++++-- ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp | 4 ++++ .../src/plugins/opmap/opmap_edit_waypoint_dialog.cpp | 2 +- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index ceece322e..079c2532f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -263,6 +263,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } void WayPointItem::SetAltitude(const float &value) { + if(altitude==value) + return; altitude=value; RefreshToolTip(); emit WPValuesChanged(this); @@ -271,13 +273,16 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { + qDebug()<<"AKI0"<Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); } RefreshPos(); RefreshToolTip(); @@ -451,7 +456,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals type_str="Absolute"; QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); - QString relativeAltitude_str="Relative altitude:"+QString::number(relativeCoord.altitudeRelative); + QString relativeAltitude_str=QString::number(relativeCoord.altitudeRelative); if(Number()!=-1) setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(Number())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); else diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index ef2111770..22a5a7176 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -46,6 +46,10 @@ void modelMapProxy::WPValuesChanged(WayPointItem * wp) model->setData(index,wp->Coord().Lat(),Qt::EditRole); index=model->index(wp->Number(),flightDataModel::LNGPOSITION); model->setData(index,wp->Coord().Lng(),Qt::EditRole); + + index=model->index(wp->Number(),flightDataModel::ALTITUDE); + model->setData(index,wp->Altitude(),Qt::EditRole); + index=model->index(wp->Number(),flightDataModel::DISRELATIVE); model->setData(index,wp->getRelativeCoord().distance,Qt::EditRole); index=model->index(wp->Number(),flightDataModel::BEARELATIVE); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 49014b91b..67c3318d3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -59,6 +59,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract mapper->addMapping(ui->doubleSpinBoxBearing,flightDataModel::BEARELATIVE); mapper->addMapping(ui->doubleSpinBoxVelocity,flightDataModel::VELOCITY); mapper->addMapping(ui->spinBoxDistance,flightDataModel::DISRELATIVE); + mapper->addMapping(ui->doubleSpinBoxRelativeAltitude,flightDataModel::ALTITUDERELATIVE); mapper->addMapping(ui->cbMode,flightDataModel::MODE); mapper->addMapping(ui->dsb_modeParam1,flightDataModel::MODE_PARAMS0); mapper->addMapping(ui->dsb_modeParam2,flightDataModel::MODE_PARAMS1); @@ -93,7 +94,6 @@ opmap_edit_waypoint_dialog::~opmap_edit_waypoint_dialog() void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() { - close(); } From b467a3e81ee88e5b15de1faee83df00ec7d5d95a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 27 Jun 2012 15:06:53 +0100 Subject: [PATCH 039/116] GCS/OPMap-Fixes compile under windows. --- .../openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index ed2ecdf10..e9048b7f8 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -195,14 +195,6 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_widget->progressBarMap->setMaximum(1); - #if defined(Q_OS_MAC) - #elif defined(Q_OS_WIN) - m_widget->comboBoxFindPlace->clear(); - loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); - m_widget->comboBoxFindPlace->setCurrentIndex(-1); - #else - #endif - connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals From 5eff06bdc12c2a6f8bf3c54f8a66e25694637007 Mon Sep 17 00:00:00 2001 From: zedamota Date: Wed, 27 Jun 2012 23:54:41 +0100 Subject: [PATCH 040/116] GCS/OPMap-Fixes compilation under windows...again... --- .../openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index d4be745b8..c238b62ad 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -62,7 +62,6 @@ private slots: private slots: void currentIndexChanged(int index); void setupModeWidgets(); - void setupPositionWidgets(bool isRelative); void setupConditionWidgets(); void pushButtonCancel_clicked(); void on_pushButtonOK_clicked(); From 70bdbf49c3a87aae631241569fcf8dbffe4512e7 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 28 Jun 2012 20:17:16 +0100 Subject: [PATCH 041/116] GCS/OPMap- Fixes bad coordinate calculation on home drag. --- .../src/mapwidget/waypointitem.cpp | 14 +++--- .../opmap/opmap_edit_waypoint_dialog.cpp | 2 +- .../opmap/opmap_edit_waypoint_dialog.ui | 46 +++++++++++-------- 3 files changed, 34 insertions(+), 28 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 079c2532f..a02289426 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -273,22 +273,21 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { - qDebug()<<"AKI0"<Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); - SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); } RefreshPos(); RefreshToolTip(); emit WPValuesChanged(this); this->update(); } + void WayPointItem::SetCoord(const internals::PointLatLng &value) { if(Coord()==value) @@ -412,6 +411,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals emit WPValuesChanged(this); } } + void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) { if (waypoint!=this) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 67c3318d3..ddb934c4e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -58,7 +58,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract mapper->addMapping(ui->checkBoxRelative,flightDataModel::ISRELATIVE); mapper->addMapping(ui->doubleSpinBoxBearing,flightDataModel::BEARELATIVE); mapper->addMapping(ui->doubleSpinBoxVelocity,flightDataModel::VELOCITY); - mapper->addMapping(ui->spinBoxDistance,flightDataModel::DISRELATIVE); + mapper->addMapping(ui->doubleSpinBoxDistance,flightDataModel::DISRELATIVE); mapper->addMapping(ui->doubleSpinBoxRelativeAltitude,flightDataModel::ALTITUDERELATIVE); mapper->addMapping(ui->cbMode,flightDataModel::MODE); mapper->addMapping(ui->dsb_modeParam1,flightDataModel::MODE_PARAMS0); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index 147296b56..a27736344 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -13,7 +13,7 @@ 0 0 606 - 387 + 420 @@ -111,7 +111,7 @@ - 7 + 5 -90.000000000000000 @@ -124,7 +124,7 @@ - 7 + 5 -180.000000000000000 @@ -164,13 +164,6 @@ - - - - 999999999 - - - @@ -197,6 +190,9 @@ + + 2 + 360.000000000000000 @@ -281,16 +277,6 @@ - - - - -5000.000000000000000 - - - 5000.000000000000000 - - - @@ -318,6 +304,26 @@ + + + + 0 + + + 999999999.000000000000000 + + + + + + + -5000.000000000000000 + + + 5000.000000000000000 + + + From 8bc83d49a5c6a39d651bca34c5117fc6600367a3 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 29 Jun 2012 01:20:38 +0100 Subject: [PATCH 042/116] GCS/OPMap-Make the overlays opacity user selectable and persistent. --- .../src/mapwidget/mapgraphicitem.cpp | 25 +++++++++++++ .../src/mapwidget/mapgraphicitem.h | 3 +- .../src/mapwidget/opmapwidget.cpp | 35 ++++++++++++++++--- .../opmapcontrol/src/mapwidget/opmapwidget.h | 3 ++ .../src/plugins/opmap/opmapgadget.cpp | 14 ++++++-- .../src/plugins/opmap/opmapgadget.h | 3 +- .../opmap/opmapgadgetconfiguration.cpp | 8 ++++- .../plugins/opmap/opmapgadgetconfiguration.h | 4 +++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 35 ++++++++++++++++++- .../src/plugins/opmap/opmapgadgetwidget.h | 5 +++ 10 files changed, 122 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 2f07898d0..494482283 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -113,6 +113,31 @@ namespace mapcontrol wwww->RefreshPos(); } } + void MapGraphicItem::setOverlayOpacity(qreal value) + { + foreach(QGraphicsItem* i,this->childItems()) + { + WayPointItem* w=qgraphicsitem_cast(i); + if(w) + w->setOpacity(value); + UAVItem* ww=qgraphicsitem_cast(i); + if(ww) + ww->setOpacity(value); + HomeItem* www=qgraphicsitem_cast(i); + if(www) + www->setOpacity(value); + GPSItem* wwww=qgraphicsitem_cast(i); + if(wwww) + wwww->setOpacity(value); + WayPointLine* wwwww=qgraphicsitem_cast(i); + if(wwwww) + wwwww->setOpacity(value); + WayPointCircle* wwwwww=qgraphicsitem_cast(i); + if(wwwwww) + wwwwww->setOpacity(value); + + } + } void MapGraphicItem::ConstructLastImage(int const& zoomdiff) { QImage temp; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index 3f96ffe8b..1d3ce17f3 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -94,7 +94,6 @@ namespace mapcontrol bool IsDragging()const{return core->IsDragging();} QImage lastimage; -// QPainter* imagePainter; core::Point lastimagepoint; void paintImage(QPainter* painter); void ConstructLastImage(int const& zoomdiff); @@ -102,7 +101,7 @@ namespace mapcontrol double Zoom(); double ZoomDigi(); double ZoomTotal(); - + void setOverlayOpacity(qreal value); protected: void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); void mousePressEvent ( QGraphicsSceneMouseEvent * event ); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 9c0198a3d..2d5426578 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -59,6 +59,7 @@ namespace mapcontrol SetShowDiagnostics(showDiag); this->setMouseTracking(followmouse); SetShowCompass(true); + overlayOpacity=1; } void OPMapWidget::SetShowDiagnostics(bool const& value) @@ -92,6 +93,7 @@ namespace mapcontrol { GPS=new GPSItem(map,this); GPS->setParentItem(map); + setOverlayOpacity(overlayOpacity); } } @@ -108,26 +110,34 @@ namespace mapcontrol { if(!from|!to) return NULL; - return new WayPointLine(from,to,map,color); + WayPointLine* ret= new WayPointLine(from,to,map,color); + setOverlayOpacity(overlayOpacity); + return ret; } WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to,QColor color) { if(!from|!to) return NULL; - return new WayPointLine(from,to,map,color); + WayPointLine* ret= new WayPointLine(from,to,map,color); + setOverlayOpacity(overlayOpacity); + return ret; } WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise,QColor color) { if(!center|!radius) return NULL; - return new WayPointCircle(center,radius,clockwise,map,color); + WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color); + setOverlayOpacity(overlayOpacity); + return ret; } WayPointCircle *OPMapWidget::WPCircleCreate(HomeItem *center, WayPointItem *radius, bool clockwise,QColor color) { if(!center|!radius) return NULL; - return new WayPointCircle(center,radius,clockwise,map,color); + WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color); + setOverlayOpacity(overlayOpacity); + return ret; } void OPMapWidget::SetShowUAV(const bool &value) { @@ -137,6 +147,7 @@ namespace mapcontrol UAV->setParentItem(map); connect(this,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng)),UAV,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng))); connect(this,SIGNAL(UAVReachedWayPoint(int,WayPointItem*)),UAV,SIGNAL(UAVReachedWayPoint(int,WayPointItem*))); + setOverlayOpacity(overlayOpacity); } else if(!value) { @@ -234,6 +245,7 @@ namespace mapcontrol item->setParentItem(map); int position=item->Number(); emit WPCreated(position,item); + setOverlayOpacity(overlayOpacity); } WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude) { @@ -242,6 +254,7 @@ namespace mapcontrol item->setParentItem(map); int position=item->Number(); emit WPCreated(position,item); + setOverlayOpacity(overlayOpacity); return item; } WayPointItem* OPMapWidget::WPCreate(internals::PointLatLng const& coord,int const& altitude, QString const& description) @@ -251,6 +264,7 @@ namespace mapcontrol item->setParentItem(map); int position=item->Number(); emit WPCreated(position,item); + setOverlayOpacity(overlayOpacity); return item; } WayPointItem* OPMapWidget::WPCreate(const distBearingAltitude &relativeCoord, const QString &description) @@ -260,6 +274,7 @@ namespace mapcontrol item->setParentItem(map); int position=item->Number(); emit WPCreated(position,item); + setOverlayOpacity(overlayOpacity); return item; } WayPointItem* OPMapWidget::WPInsert(const int &position) @@ -269,6 +284,7 @@ namespace mapcontrol ConnectWP(item); item->setParentItem(map); emit WPInserted(position,item); + setOverlayOpacity(overlayOpacity); return item; } void OPMapWidget::WPInsert(WayPointItem* item,const int &position) @@ -277,7 +293,7 @@ namespace mapcontrol ConnectWP(item); item->setParentItem(map); emit WPInserted(position,item); - + setOverlayOpacity(overlayOpacity); } WayPointItem* OPMapWidget::WPInsert(internals::PointLatLng const& coord,int const& altitude,const int &position) { @@ -286,6 +302,7 @@ namespace mapcontrol ConnectWP(item); item->setParentItem(map); emit WPInserted(position,item); + setOverlayOpacity(overlayOpacity); return item; } WayPointItem* OPMapWidget::WPInsert(internals::PointLatLng const& coord,int const& altitude, QString const& description,const int &position) @@ -306,6 +323,7 @@ namespace mapcontrol emit WPInserted(position,item); if(reloc) emit WPValuesChanged(item); + setOverlayOpacity(overlayOpacity); return item; } WayPointItem* OPMapWidget::WPInsert(distBearingAltitude const& relative, QString const& description,const int &position) @@ -315,6 +333,7 @@ namespace mapcontrol ConnectWP(item); item->setParentItem(map); emit WPInserted(position,item); + setOverlayOpacity(overlayOpacity); return item; } void OPMapWidget::WPDelete(WayPointItem *item) @@ -481,6 +500,12 @@ namespace mapcontrol compass=0; } } + + void OPMapWidget::setOverlayOpacity(qreal value) + { + map->setOverlayOpacity(value); + overlayOpacity=value; + } void OPMapWidget::SetRotate(qreal const& value) { map->mapRotate(value); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 98255e6fd..16e1eb766 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -353,6 +353,8 @@ namespace mapcontrol void SetShowCompass(bool const& value); + void setOverlayOpacity(qreal value); + UAVItem* UAV; GPSItem* GPS; HomeItem* Home; @@ -390,6 +392,7 @@ namespace mapcontrol QTimer * diagTimer; QGraphicsTextItem * diagGraphItem; bool showDiag; + qreal overlayOpacity; private slots: void diagRefresh(); // WayPointItem* item;//apagar diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp index 192575a55..5ad7cb1db 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp @@ -31,14 +31,15 @@ OPMapGadget::OPMapGadget(QString classId, OPMapGadgetWidget *widget, QWidget *pa IUAVGadget(classId, parent), m_widget(widget),m_config(NULL) { - connect(m_widget,SIGNAL(defaultLocationAndZoomChanged(double,double,double)),this,SLOT(saveConfiguration(double,double,double))); + connect(m_widget,SIGNAL(defaultLocationAndZoomChanged(double,double,double)),this,SLOT(saveDefaultLocation(double,double,double))); + connect(m_widget,SIGNAL(overlayOpacityChanged(qreal)),this,SLOT(saveOpacity(qreal))); } OPMapGadget::~OPMapGadget() { delete m_widget; } -void OPMapGadget::saveConfiguration(double lng,double lat,double zoom) +void OPMapGadget::saveDefaultLocation(double lng,double lat,double zoom) { if(m_config) { @@ -49,6 +50,13 @@ void OPMapGadget::saveConfiguration(double lng,double lat,double zoom) } } +void OPMapGadget::saveOpacity(qreal value) +{ + if(m_config) + { + m_config->setOpacity(value); + } +} void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) { m_config = qobject_cast(config); @@ -62,6 +70,6 @@ void OPMapGadget::loadConfiguration(IUAVGadgetConfiguration *config) m_widget->setZoom(m_config->zoom()); m_widget->setPosition(QPointF(m_config->longitude(), m_config->latitude())); m_widget->setHomePosition(QPointF(m_config->longitude(), m_config->latitude())); - + m_widget->setOverlayOpacity(m_config->opacity()); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h index eb69255fa..d83b01782 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h @@ -52,7 +52,8 @@ private: OPMapGadgetWidget *m_widget; OPMapGadgetConfiguration *m_config; private slots: - void saveConfiguration(double lng, double lat, double zoom); + void saveOpacity(qreal value); + void saveDefaultLocation(double lng, double lat, double zoom); }; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp index 7e77b0031..2e1465365 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp @@ -42,7 +42,8 @@ OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()), m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")), m_maxUpdateRate(2000), // ms - m_settings(qSettings) + m_settings(qSettings), + m_opacity(1) { //if a saved configuration exists load it @@ -60,6 +61,8 @@ OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* QString uavSymbol=qSettings->value("uavSymbol").toString(); int max_update_rate = qSettings->value("maxUpdateRate").toInt(); + m_opacity=qSettings->value("overlayOpacity",1).toReal(); + if (!mapProvider.isEmpty()) m_mapProvider = mapProvider; m_defaultZoom = zoom; m_defaultLatitude = latitude; @@ -95,6 +98,7 @@ IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone() m->m_cacheLocation = m_cacheLocation; m->m_uavSymbol = m_uavSymbol; m->m_maxUpdateRate = m_maxUpdateRate; + m->m_opacity=m_opacity; return m; } @@ -112,6 +116,7 @@ void OPMapGadgetConfiguration::saveConfig() const { m_settings->setValue("uavSymbol", m_uavSymbol); m_settings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); m_settings->setValue("maxUpdateRate", m_maxUpdateRate); + m_settings->setValue("overlayOpacity",m_opacity); } void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("mapProvider", m_mapProvider); @@ -125,6 +130,7 @@ void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { qSettings->setValue("uavSymbol", m_uavSymbol); qSettings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); qSettings->setValue("maxUpdateRate", m_maxUpdateRate); + qSettings->setValue("overlayOpacity",m_opacity); } void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){ m_cacheLocation = cacheLocation; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h index ffd0c5a08..0efb87050 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h @@ -48,6 +48,7 @@ Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache) Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation) Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol) Q_PROPERTY(int maxUpdateRate READ maxUpdateRate WRITE setMaxUpdateRate) +Q_PROPERTY(qreal overlayOpacity READ opacity WRITE setOpacity) public: explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); @@ -66,11 +67,13 @@ public: QString cacheLocation() const { return m_cacheLocation; } QString uavSymbol() const { return m_uavSymbol; } int maxUpdateRate() const { return m_maxUpdateRate; } + qreal opacity() const { return m_opacity; } void saveConfig() const; public slots: void setMapProvider(QString provider) { m_mapProvider = provider; } void setZoom(int zoom) { m_defaultZoom = zoom; } void setLatitude(double latitude) { m_defaultLatitude = latitude; } + void setOpacity(qreal value) { m_opacity = value; } void setLongitude(double longitude) { m_defaultLongitude = longitude; } void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; } void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; } @@ -93,6 +96,7 @@ private: QString m_uavSymbol; int m_maxUpdateRate; QSettings * m_settings; + qreal m_opacity; }; #endif // OPMAP_GADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index e9048b7f8..8fa6ac84c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -220,6 +220,8 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) magicWayPoint=m_map->magicWPCreate(); magicWayPoint->setVisible(false); + m_map->setOverlayOpacity(0.5); + // ************** // create various context menu (mouse right click menu) actions @@ -504,6 +506,10 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) // ********* + QMenu overlaySubMenu(tr("&Overlay Opacity "),this); + for (int i = 0; i < overlayOpacityAct.count(); i++) + overlaySubMenu.addAction(overlayOpacityAct.at(i)); + contextMenu.addMenu(&overlaySubMenu); contextMenu.addSeparator(); contextMenu.addAction(closeAct2); @@ -676,7 +682,7 @@ void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) int index0_zoom = i_zoom - m_min_zoom; // zoom level starting at index level '0' if (index0_zoom < zoomAct.count()) - zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level + zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level } void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) @@ -987,6 +993,14 @@ void OPMapGadgetWidget::setZoom(int zoom) m_map->SetMouseWheelZoomType(zoom_type); } +void OPMapGadgetWidget::setOverlayOpacity(qreal value) +{ + if (!m_widget || !m_map) + return; + m_map->setOverlayOpacity(value); + overlayOpacityAct.at(value*10)->setChecked(true); +} + void OPMapGadgetWidget::setHomePosition(QPointF pos) { if (!m_widget || !m_map) @@ -1302,6 +1316,16 @@ void OPMapGadgetWidget::createActions() clearWayPointsAct->setStatusTip(tr("Clear waypoints")); connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); + overlayOpacityActGroup = new QActionGroup(this); + connect(overlayOpacityActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onOverlayOpacityActGroup_triggered(QAction *))); + overlayOpacityAct.clear(); + for (int i = 0; i <= 10; i++) + { + QAction *overlayAct = new QAction(QString::number(i*10), overlayOpacityActGroup); + overlayAct->setCheckable(true); + overlayAct->setData(i*10); + overlayOpacityAct.append(overlayAct); + } homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position")); @@ -2089,3 +2113,12 @@ void OPMapGadgetWidget::onHomeDoubleClick(HomeItem *) { new homeEditor(m_map->Home,this); } + +void OPMapGadgetWidget::onOverlayOpacityActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + m_map->setOverlayOpacity(action->data().toReal()/100); + emit overlayOpacityChanged(action->data().toReal()/100); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index b7ab82909..5d844fb57 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -115,8 +115,10 @@ public: void SetUavPic(QString UAVPic); void setMaxUpdateRate(int update_rate); void setHomePosition(QPointF pos); + void setOverlayOpacity(qreal value); signals: void defaultLocationAndZoomChanged(double lng,double lat,double zoom); + void overlayOpacityChanged(qreal); public slots: void homePositionUpdated(UAVObject *); @@ -207,6 +209,7 @@ private slots: void onChangeDefaultLocalAndZoom(); void on_tbFind_clicked(); void onHomeDoubleClick(HomeItem*); + void onOverlayOpacityActGroup_triggered(QAction *action); private: int m_min_zoom; int m_max_zoom; @@ -281,7 +284,9 @@ private: QList mapModeAct; QActionGroup *zoomActGroup; + QActionGroup *overlayOpacityActGroup; QList zoomAct; + QList overlayOpacityAct; QActionGroup *maxUpdateRateActGroup; QList maxUpdateRateAct; From d2d4d4dabd17148d30cc6c88653c8b94859f2a7e Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 5 Jul 2012 19:24:41 +0100 Subject: [PATCH 043/116] GCS/OPMap-Move line path arrow to the midle of the line. --- .../src/libs/opmapcontrol/src/mapwidget/waypointline.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 938d01246..1f08ca27f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -73,14 +73,12 @@ void WayPointLine::paint(QPainter *painter, const QStyleOptionGraphicsItem *opti if (line().dy() >= 0) angle = (Pi * 2) - angle; - QPointF arrowP1 = line().p1() + QPointF(sin(angle + Pi / 3) * arrowSize, + QPointF arrowP1 = line().pointAt(0.5) + QPointF(sin(angle + Pi / 3) * arrowSize, cos(angle + Pi / 3) * arrowSize); - QPointF arrowP2 = line().p1() + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, + QPointF arrowP2 = line().pointAt(0.5) + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, cos(angle + Pi - Pi / 3) * arrowSize); - arrowHead.clear(); - arrowHead << line().p1() << arrowP1 << arrowP2; -//! [6] //! [7] + arrowHead << line().pointAt(0.5) << arrowP1 << arrowP2; painter->drawLine(line()); painter->drawPolygon(arrowHead); } From fa643e8dbb23e73bff761fee4665f049217b1761 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Thu, 28 Jun 2012 13:19:11 +0300 Subject: [PATCH 044/116] GCS/OPMap-Added tooltip to home location in waypoint editor. --- .../opmapcontrol/src/mapwidget/homeitem.cpp | 17 ++++++++++++++++- .../libs/opmapcontrol/src/mapwidget/homeitem.h | 2 ++ 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 1b97aa8d0..d05b612a9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -38,9 +38,17 @@ namespace mapcontrol this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); coord=internals::PointLatLng(50,50); - setToolTip("AAAA"); + RefreshToolTip(); } + void HomeItem::RefreshToolTip() + { + QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); + + setToolTip(QString("Waypoint: Home\nCoordinate:%1\nAltitude:%2\n").arg(coord_str).arg(QString::number(altitude))); + } + + void HomeItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) { Q_UNUSED(option); @@ -70,6 +78,7 @@ namespace mapcontrol { return Type; } + void HomeItem::RefreshPos() { prepareGeometryChange(); @@ -78,7 +87,10 @@ namespace mapcontrol if(showsafearea) localsafearea=safearea/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); + RefreshToolTip(); + } + void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { if(event->button()==Qt::LeftButton) @@ -87,6 +99,7 @@ namespace mapcontrol } QGraphicsItem::mousePressEvent(event); } + void HomeItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) { if(event->button()==Qt::LeftButton) @@ -97,6 +110,8 @@ namespace mapcontrol emit homePositionChanged(coord,Altitude()); } QGraphicsItem::mouseReleaseEvent(event); + + RefreshToolTip(); } void HomeItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index 8aab6a58c..c3bdd4f3f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -57,7 +57,9 @@ namespace mapcontrol internals::PointLatLng Coord()const{return coord;} void SetAltitude(float const& value){altitude=value;emit homePositionChanged(Coord(),Altitude());} float Altitude()const{return altitude;} + void RefreshToolTip(); private: + MapGraphicItem* map; OPMapWidget* mapwidget; QPixmap pic; From 9938f221e1b8dddacc2f62f59b602cef71d6035b Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Thu, 28 Jun 2012 13:21:07 +0300 Subject: [PATCH 045/116] GCS/OPMap-Improved dialog message in mac ripper. We might also want to rename module, as "rip" is a somewhat loaded word. Pre-cache might be more neutral. --- .../src/libs/opmapcontrol/src/mapwidget/mapripper.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index bbda543d6..04f33c20b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -49,7 +49,11 @@ MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect) emit numberOfTilesChanged(0,0); } else - QMessageBox::information(new QWidget(),"No valid selection","Please select the area of the map to rip with Mouse+Control key"); +#ifdef Q_OS_DARWIN + QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); +#else + QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); +#endif } void MapRipper::finish() { From 2d94e29fd9bc4b1a943b86fa7bed785556561aa7 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Thu, 28 Jun 2012 14:59:42 +0300 Subject: [PATCH 046/116] GCS/OPMap-Added dialog box to confirm on clear waypoints. Also fixed some indenting. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 22 +++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8fa6ac84c..7cea6542a 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1713,11 +1713,12 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) if (m_map_mode != Normal_MapMode) return; - // m_map->WPCreate(coord, 0, ""); - mapProxy->createWayPoint(coord); + // m_map->WPCreate(coord, 0, ""); + float alt=15; + mapProxy->createWayPoint(coord, alt); - //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); } @@ -1784,6 +1785,19 @@ void OPMapGadgetWidget::onDeleteWayPointAct_triggered() void OPMapGadgetWidget::onClearWayPointsAct_triggered() { + + //First, ask to ensure this is what the user wants to do + QMessageBox msgBox; + msgBox.setText(tr("Are you sure you want to clear waypoints?")); + msgBox.setInformativeText(tr("All associated data will be lost.")); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); + int ret = msgBox.exec(); + + if (ret == QMessageBox::No) + { + return; + } + if (!m_widget || !m_map) return; From 68fba8030128a5e6b3769431667b3ce29d0eff98 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 5 Jul 2012 21:58:23 +0100 Subject: [PATCH 047/116] GCS/OPMap-Add remove leg button functionality. --- ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp index 532e198c2..95dbcacf6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -78,7 +78,7 @@ void pathPlanner::on_tbAdd_clicked() void pathPlanner::on_tbDelete_clicked() { - + ui->tableView->model()->removeRow(ui->tableView->selectionModel()->currentIndex().row()); } void pathPlanner::on_tbInsert_clicked() From 2fa4afd4a7f28c77ecb886b31e3af3399c3d48d0 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Thu, 5 Jul 2012 22:44:39 +0100 Subject: [PATCH 048/116] GCS/OPMap-Make the wp editor show on wp doubleclick if it is already open --- .../src/plugins/opmap/opmap_edit_waypoint_dialog.cpp | 11 +++++++++-- .../src/plugins/opmap/opmapgadgetwidget.cpp | 9 ++------- 2 files changed, 11 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index ddb934c4e..eb60f60b9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -33,7 +33,7 @@ // constructor opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstractItemModel * model,QItemSelectionModel * selection) : - QWidget(parent),model(model),itemSelection(selection), + QWidget(parent,Qt::Window),model(model),itemSelection(selection), ui(new Ui::opmap_edit_waypoint_dialog) { ui->setupUi(this); @@ -235,7 +235,14 @@ void opmap_edit_waypoint_dialog::pushButtonCancel_clicked() void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) return; - show(); + if(!isVisible()) + show(); + if(isMinimized()) + showNormal(); + if(!isActiveWindow()) + activateWindow(); + raise(); + setFocus(Qt::OtherFocusReason); mapper->setCurrentIndex(waypoint_item->Number()); } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 7cea6542a..9e22625f3 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -212,7 +212,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) selectionModel=new QItemSelectionModel(model); mapProxy=new modelMapProxy(this,m_map,model,selectionModel); table->setModel(model,selectionModel); - waypoint_edit_dialog=new opmap_edit_waypoint_dialog(NULL,model,selectionModel); + waypoint_edit_dialog=new opmap_edit_waypoint_dialog(this,model,selectionModel); UAVProxy=new modelUavoProxy(this,model); connect(table,SIGNAL(sendPathPlanToUAV()),UAVProxy,SLOT(modelToObjects())); connect(table,SIGNAL(receivePathPlanFromUAV()),UAVProxy,SLOT(objectsToModel())); @@ -1712,13 +1712,8 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) if (m_map_mode != Normal_MapMode) return; - - // m_map->WPCreate(coord, 0, ""); float alt=15; - mapProxy->createWayPoint(coord, alt); - - //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - //wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + mapProxy->createWayPoint(coord); } From de633d1bccee7d7cc79a965f4f4f955943c44fe0 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 11:25:35 +0100 Subject: [PATCH 049/116] GCS/OPMap-Give lines of different colors different widths and z orders. --- .../src/mapwidget/waypointline.cpp | 22 ++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 1f08ca27f..748c4ca1d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -39,6 +39,12 @@ WayPointLine::WayPointLine(WayPointItem *from, WayPointItem *to, MapGraphicItem connect(to,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); connect(from,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + if(myColor==Qt::green) + this->setZValue(10); + else if(myColor==Qt::yellow) + this->setZValue(9); + else if(myColor==Qt::red) + this->setZValue(8); } WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map, QColor color):source(from), @@ -48,6 +54,12 @@ WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map connect(from,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(refreshLocations())); connect(to,SIGNAL(localPositionChanged(QPointF,WayPointItem*)),this,SLOT(refreshLocations())); connect(to,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); + if(myColor==Qt::green) + this->setZValue(10); + else if(myColor==Qt::yellow) + this->setZValue(9); + else if(myColor==Qt::red) + this->setZValue(8); } int WayPointLine::type() const { @@ -79,8 +91,16 @@ void WayPointLine::paint(QPainter *painter, const QStyleOptionGraphicsItem *opti cos(angle + Pi - Pi / 3) * arrowSize); arrowHead.clear(); arrowHead << line().pointAt(0.5) << arrowP1 << arrowP2; - painter->drawLine(line()); painter->drawPolygon(arrowHead); + if(myColor==Qt::red) + myPen.setWidth(3); + else if(myColor==Qt::yellow) + myPen.setWidth(2); + else if(myColor==Qt::green) + myPen.setWidth(1); + painter->setPen(myPen); + painter->drawLine(line()); + } void WayPointLine::refreshLocations() From 96fb46b38dfa11734e107d86585a698d95e61973 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 11:26:27 +0100 Subject: [PATCH 050/116] GCS/OPMap-comment cleaning --- .../opmapcontrol/src/mapwidget/traillineitem.cpp | 12 +----------- ground/uavobjects/uavobjects.pro | 1 + 2 files changed, 2 insertions(+), 11 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp index c7cd05694..9dfe5d584 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp @@ -36,17 +36,7 @@ namespace mapcontrol pen.setWidth(1); this->setPen(pen); } -/* - void TrailLineItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) - { - // painter->drawRect(QRectF(-3,-3,6,6)); - painter->setBrush(m_brush); - QPen pen; - pen.setBrush(m_brush); - pen.setWidth(2); - painter->drawLine(this->line().x1(),this->line().y1(),this->line().x2(),this->line().y2()); - } -*/ + int TrailLineItem::type()const { return Type; diff --git a/ground/uavobjects/uavobjects.pro b/ground/uavobjects/uavobjects.pro index 4e2c0c66e..5a256ba3d 100644 --- a/ground/uavobjects/uavobjects.pro +++ b/ground/uavobjects/uavobjects.pro @@ -20,6 +20,7 @@ isEmpty(QMAKESPEC) { win32:SPEC = win32-g++ macx-g++:SPEC = macx-g++ linux-g++:SPEC = linux-g++ + linux-g++-32:SPEC = linux-g++ linux-g++-64:SPEC = linux-g++-64 } else { SPEC = $$QMAKESPEC From 71a35b2dd8fef52d00c543693ff074b60d95e8b1 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 21:57:43 +0100 Subject: [PATCH 051/116] GCS/OPMap-make the waypoint numbers start with 1. This is only visual, internal implementation is still zero based --- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 6 +++--- .../src/libs/opmapcontrol/src/mapwidget/waypointitem.h | 1 + ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp | 2 +- .../src/plugins/opmap/opmap_edit_waypoint_dialog.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- 5 files changed, 7 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index a02289426..4e3a97cf7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -322,7 +322,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals int oldnumber=number; number=value; RefreshToolTip(); - numberI->setText(QString::number(number)); + numberI->setText(QString::number(numberAdjusted())); numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); this->update(); emit WPNumberChanged(oldnumber,value,this); @@ -363,7 +363,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals numberI->setPen(QPen(Qt::blue)); numberI->setPos(0,-13-picture.height()); numberIBG->setPos(0,-13-picture.height()); - numberI->setText(QString::number(number)); + numberI->setText(QString::number(numberAdjusted())); numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); } else if (!value && numberI) @@ -458,7 +458,7 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); QString relativeAltitude_str=QString::number(relativeCoord.altitudeRelative); if(Number()!=-1) - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(Number())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(numberAdjusted())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); else setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index d90d1bf4b..df5f3b5e9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -109,6 +109,7 @@ public: * */ int Number(){return number;} + int numberAdjusted(){return number+1;} /** * @brief Sets WayPoint number * diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index 7d84a6839..cbfb3ad31 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -250,7 +250,7 @@ QVariant flightDataModel::headerData(int section, Qt::Orientation orientation, i { if(orientation==Qt::Vertical) { - return QString::number(section); + return QString::number(section+1); } else if (orientation == Qt::Horizontal) { switch (section) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index eb60f60b9..8795bee30 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -79,7 +79,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract } void opmap_edit_waypoint_dialog::currentIndexChanged(int index) { - ui->lbNumber->setText(QString::number(index)); + ui->lbNumber->setText(QString::number(index+1)); QModelIndex idx=mapper->model()->index(index,0); if(index==itemSelection->currentIndex().row()) return; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 9e22625f3..8f7351f1b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -636,7 +636,7 @@ void OPMapGadgetWidget::updateMousePos() QString s = QString::number(m_mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_mouse_lat_lon.Lng(), 'f', 7); if (wp) { - s += " wp[" + QString::number(wp->Number()) + "]"; + s += " wp[" + QString::number(wp->numberAdjusted()) + "]"; double dist = distance(home_lat_lon, wp->Coord()); double bear = bearing(home_lat_lon, wp->Coord()); From 66ed4552be0fa39ee5dd5495d3c38b7c90f4cca8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 22:57:20 +0100 Subject: [PATCH 052/116] GCS/OPMap-add apply and cancel buttons to the wp editor --- .../plugins/opmap/opmap_edit_waypoint_dialog.cpp | 14 ++++++++++---- .../src/plugins/opmap/opmap_edit_waypoint_dialog.h | 2 +- .../plugins/opmap/opmap_edit_waypoint_dialog.ui | 14 ++++++++++++++ 3 files changed, 25 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 8795bee30..32ae8887e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -37,11 +37,11 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract ui(new Ui::opmap_edit_waypoint_dialog) { ui->setupUi(this); - my_waypoint = NULL; connect(ui->checkBoxLocked,SIGNAL(toggled(bool)),this,SLOT(enableEditWidgets(bool))); connect(ui->cbMode,SIGNAL(currentIndexChanged(int)),this,SLOT(setupModeWidgets())); connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets())); - + connect(ui->pushButtonApply,SIGNAL(clicked()),this,SLOT(pushButtonApply_clicked())); + connect(ui->pushButtonCancel,SIGNAL(clicked()),this,SLOT(pushButtonCancel_clicked())); mapDataDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); mapDataDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); mapDataDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); @@ -50,6 +50,7 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract mapper->setItemDelegate(new mapDataDelegate(this)); connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(currentIndexChanged(int))); mapper->setModel(model); + mapper->setSubmitPolicy(QDataWidgetMapper::ManualSubmit); mapper->addMapping(ui->checkBoxLocked,flightDataModel::LOCKED); mapper->addMapping(ui->doubleSpinBoxLatitude,flightDataModel::LATPOSITION); mapper->addMapping(ui->doubleSpinBoxLongitude,flightDataModel::LNGPOSITION); @@ -94,6 +95,7 @@ opmap_edit_waypoint_dialog::~opmap_edit_waypoint_dialog() void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() { + mapper->submit(); close(); } @@ -226,12 +228,16 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() break; } } + void opmap_edit_waypoint_dialog::pushButtonCancel_clicked() { - my_waypoint = NULL; + mapper->revert(); close(); } - +void opmap_edit_waypoint_dialog::pushButtonApply_clicked() +{ + mapper->submit(); +} void opmap_edit_waypoint_dialog::editWaypoint(mapcontrol::WayPointItem *waypoint_item) { if (!waypoint_item) return; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index c238b62ad..55368fdd6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -53,7 +53,6 @@ public: private: Ui::opmap_edit_waypoint_dialog *ui; - mapcontrol::WayPointItem * my_waypoint; QDataWidgetMapper *mapper; QAbstractItemModel * model; QItemSelectionModel * itemSelection; @@ -65,6 +64,7 @@ private slots: void setupConditionWidgets(); void pushButtonCancel_clicked(); void on_pushButtonOK_clicked(); + void pushButtonApply_clicked(); void on_pushButton_clicked(); void on_pushButton_2_clicked(); void enableEditWidgets(bool); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui index a27736344..a87a0534f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.ui @@ -780,6 +780,20 @@ + + + + Apply + + + + + + + Cancel + + + From 61dea64a765bd3ee3b22eb16806699bbc12fd59d Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Fri, 6 Jul 2012 23:02:56 +0100 Subject: [PATCH 053/116] GCS/OPMap-Increase several value limits and added missing label on the wp editor. --- .../src/mapwidget/waypointitem.cpp | 8 ++++--- .../src/plugins/opmap/flightdatamodel.cpp | 2 ++ .../opmap/opmap_edit_waypoint_dialog.ui | 24 ++++++++++++++++--- .../src/plugins/opmap/widgetdelegates.cpp | 2 ++ 4 files changed, 30 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 4e3a97cf7..d7f62c8fd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -273,9 +273,10 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { - if(value.altitudeRelative-relativeCoord.altitudeRelative<0.0001 - && value.bearing-relativeCoord.bearing<0.0001 && value.distance==relativeCoord.distance) + if(qAbs(value.altitudeRelative-relativeCoord.altitudeRelative<0.0001) + && qAbs(value.bearing-relativeCoord.bearing<0.0001) && value.distance==relativeCoord.distance) return; + qDebug()<<"setRelative"; relativeCoord=value; if(myHome) { @@ -290,8 +291,9 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::SetCoord(const internals::PointLatLng &value) { - if(Coord()==value) + if(qAbs(Coord().Lat()-value.Lat()<0.0001 && qAbs(Coord().Lng()-value.Lng()<0.0001))) return; + qDebug()<<"setCoord"; bool abs_coord=false; bool rel_coord=false; if(coord!=value) diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index cbfb3ad31..a1aafb21f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -389,6 +389,8 @@ bool flightDataModel::insertRows(int row, int count, const QModelIndex &/*parent bool flightDataModel::removeRows(int row, int count, const QModelIndex &/*parent*/) { + if(row<0) + return false; beginRemoveRows(QModelIndex(),row,row+count-1); for(int x=0; x - + + + 999999999.000000000000000 + + @@ -295,7 +299,14 @@ - + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + @@ -307,7 +318,7 @@ - 0 + 2 999999999.000000000000000 @@ -324,6 +335,13 @@ + + + + m/s + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp index d2297856d..99f21d966 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -64,6 +64,8 @@ QWidget *mapDataDelegate::createEditor(QWidget *parent, void mapDataDelegate::setEditorData(QWidget *editor, const QModelIndex &index) const { + if(!index.isValid()) + return; QString className=editor->metaObject()->className(); if (className.contains("QComboBox")) { int value = index.model()->data(index, Qt::EditRole).toInt(); From 42d06ef7d957e0a88043d605013cbaa302ee7c65 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 7 Jul 2012 16:05:28 +0100 Subject: [PATCH 054/116] GCS/OPMap-fixes math error which was causing wrong wp location and high processor usage --- .../src/internals/pureprojection.cpp | 12 +++--- .../src/mapwidget/waypointitem.cpp | 39 ++++++++++++------- 2 files changed, 30 insertions(+), 21 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index ea29e171a..2f52aff6f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -217,14 +217,14 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) } double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) { - double lon1=p1.Lng()* (PI / 180);; - double lat1=p1.Lat()* (PI / 180);; - double lon2=p2.Lng()* (PI / 180);; - double lat2=p2.Lat()* (PI / 180);; + + double lon1=p1.Lng()* (M_PI / 180);; + double lat1=p1.Lat()* (M_PI / 180);; + double lon2=p2.Lng()* (M_PI / 180);; + double lat2=p2.Lat()* (M_PI / 180);; return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2), - cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*PI); - + cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*M_PI); } double PureProjection::DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index d7f62c8fd..929ffa0c9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -266,6 +266,10 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals if(altitude==value) return; altitude=value; + if(myHome) + { + relativeCoord.altitudeRelative=altitude-myHome->Altitude(); + } RefreshToolTip(); emit WPValuesChanged(this); this->update(); @@ -273,42 +277,47 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { - if(qAbs(value.altitudeRelative-relativeCoord.altitudeRelative<0.0001) - && qAbs(value.bearing-relativeCoord.bearing<0.0001) && value.distance==relativeCoord.distance) + qDebug()<<"SetRelative("<Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetCoord(map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing)); SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); } RefreshPos(); RefreshToolTip(); emit WPValuesChanged(this); this->update(); + qDebug()<<"setRelativeCoord EXIT"; } void WayPointItem::SetCoord(const internals::PointLatLng &value) { - if(qAbs(Coord().Lat()-value.Lat()<0.0001 && qAbs(Coord().Lng()-value.Lng()<0.0001))) + qDebug()<<"1 SetCoord("<Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - if(back.distance!=relativeCoord.distance||back.bearing!=relativeCoord.bearing) - rel_coord=true; - if(abs_coord||rel_coord) - emit WPValuesChanged(this); + map->Projection()->offSetFromLatLngs(myHome->Coord(),Coord(),back.distance,back.bearing); + if(qAbs(back.bearing-relativeCoord.bearing)>0.01 || qAbs(back.distance-relativeCoord.distance)>0.1) + { + qDebug()<<"4 setCoord-relative coordinates where also updated"; + relativeCoord=back; + } + emit WPValuesChanged(this); RefreshPos(); RefreshToolTip(); this->update(); + qDebug()<<"5 setCoord EXIT"; } void WayPointItem::SetDescription(const QString &value) { From 3879baf26353ed16f5237a6bf6ee858862cf4d39 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 14 Jul 2012 20:14:42 +0100 Subject: [PATCH 055/116] GCS/OPMap-Fixes the jump and error destination number --- ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp | 8 ++++++-- ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp | 8 ++++---- 2 files changed, 10 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index 22a5a7176..c76ab9a7f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -159,8 +159,8 @@ void modelMapProxy::refreshOverlays() for(int x=0;xrowCount();++x) { wp_current=findWayPointNumber(x); - wp_jump=model->data(model->index(x,flightDataModel::JUMPDESTINATION)).toInt(); - wp_error=model->data(model->index(x,flightDataModel::ERRORDESTINATION)).toInt(); + wp_jump=model->data(model->index(x,flightDataModel::JUMPDESTINATION)).toInt()-1; + wp_error=model->data(model->index(x,flightDataModel::ERRORDESTINATION)).toInt()-1; wp_next_overlay=overlayTranslate(model->data(model->index(x+1,flightDataModel::MODE)).toInt()); wp_jump_overlay=overlayTranslate(model->data(model->index(wp_jump,flightDataModel::MODE)).toInt()); wp_error_overlay=overlayTranslate(model->data(model->index(wp_error,flightDataModel::MODE)).toInt()); @@ -331,6 +331,10 @@ void modelMapProxy::createWayPoint(internals::PointLatLng coord) model->setData(index,coord.Lat(),Qt::EditRole); index=model->index(model->rowCount()-1,flightDataModel::LNGPOSITION,QModelIndex()); model->setData(index,coord.Lng(),Qt::EditRole); + index=model->index(model->rowCount()-1,flightDataModel::JUMPDESTINATION,QModelIndex()); + model->setData(index,1,Qt::EditRole); + index=model->index(model->rowCount()-1,flightDataModel::ERRORDESTINATION,QModelIndex()); + model->setData(index,1,Qt::EditRole); } void modelMapProxy::deleteAll() { diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp index 16ba0a040..bff405364 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -106,9 +106,9 @@ void modelUavoProxy::modelToObjects() index=myModel->index(x,flightDataModel::COMMAND); action.Command=myModel->data(index).toInt(); index=myModel->index(x,flightDataModel::JUMPDESTINATION); - action.JumpDestination=myModel->data(index).toInt(); + action.JumpDestination=myModel->data(index).toInt()-1; index=myModel->index(x,flightDataModel::ERRORDESTINATION); - action.ErrorDestination=myModel->data(index).toInt(); + action.ErrorDestination=myModel->data(index).toInt()-1; int actionNumber=addAction(act,action,lastaction); if(actionNumber>lastaction) @@ -178,10 +178,10 @@ void modelUavoProxy::objectsToModel() myModel->setData(index,actionfields.EndCondition); index=myModel->index(x,flightDataModel::ERRORDESTINATION); - myModel->setData(index,actionfields.ErrorDestination); + myModel->setData(index,actionfields.ErrorDestination+1); index=myModel->index(x,flightDataModel::JUMPDESTINATION); - myModel->setData(index,actionfields.JumpDestination); + myModel->setData(index,actionfields.JumpDestination+1); index=myModel->index(x,flightDataModel::MODE); myModel->setData(index,actionfields.Mode); From 1d42b64965d761f3fa55f3944452ebfb4fb1939a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 1 Aug 2012 13:41:22 +0100 Subject: [PATCH 056/116] GCS-Kenz arrow and text request - 5$ please --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 30 +++++++++++++++++++ .../libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- 2 files changed, 31 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index bb18ab3f5..1e8c536d5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -26,6 +26,8 @@ */ #include "../internals/pureprojection.h" #include "uavitem.h" +const qreal Pi = 3.14; + namespace mapcontrol { UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) @@ -55,7 +57,35 @@ namespace mapcontrol { Q_UNUSED(option); Q_UNUSED(widget); + QLineF line(0,0,1.0,1.0); + QPen myPen; + QColor myColor(Qt::red); + painter->setPen(myPen); + line.setP1(QPointF(0,0)); + line.setLength(60.0); + line.setAngle(90.0); + myPen.setColor(myColor); + qreal arrowSize = 10; + painter->setPen(myPen); + painter->setBrush(myColor); + + double angle = ::acos(line.dx() / line.length()); + if (line.dy() <= 0) + angle = (Pi * 2) - angle; + + QPointF arrowP1 = line.pointAt(1) + QPointF(sin(angle + Pi / 3) * arrowSize, + cos(angle + Pi / 3) * arrowSize); + QPointF arrowP2 = line.pointAt(1) + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, + cos(angle + Pi - Pi / 3) * arrowSize); + arrowHead.clear(); + arrowHead << line.pointAt(1) << arrowP1 << arrowP2; + painter->drawPolygon(arrowHead); + painter->setPen(myPen); + painter->drawLine(line); painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); + qreal rot=this->rotation(); + painter->rotate(-1*rot); + painter->drawText(QPointF(10,10),"KENZ"); } QRectF UAVItem::boundingRect()const diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index ca41a3d3d..972749869 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -195,7 +195,7 @@ namespace mapcontrol void SetUavPic(QString UAVPic); private: MapGraphicItem* map; - + QPolygonF arrowHead; int altitude; UAVMapFollowType::Types mapfollowtype; UAVTrailType::Types trailtype; From 3b9e3c0054493a5b9b51712dffe24663373b244f Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Thu, 2 Aug 2012 10:58:55 +0200 Subject: [PATCH 057/116] Added support for trend lines and text info on map. --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 140 ++++++++++++++++-- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 30 ++++ .../src/plugins/hitlnew/xplanesimulator.cpp | 14 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 54 ++++++- 4 files changed, 215 insertions(+), 23 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 1e8c536d5..1aea4fc7d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -26,12 +26,13 @@ */ #include "../internals/pureprojection.h" #include "uavitem.h" + const qreal Pi = 3.14; namespace mapcontrol { UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100) + ,autosetdistance(100),altitude(0) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,true); @@ -57,18 +58,35 @@ namespace mapcontrol { Q_UNUSED(option); Q_UNUSED(widget); - QLineF line(0,0,1.0,1.0); + + QPen myPen; - QColor myColor(Qt::red); - painter->setPen(myPen); - line.setP1(QPointF(0,0)); - line.setLength(60.0); - line.setAngle(90.0); - myPen.setColor(myColor); + + //Turn on anti-aliasing so the fonts don't look terrible + painter->setRenderHint(QPainter::Antialiasing, true); + qreal arrowSize = 10; + + //Set pen attributes + QColor myColor(Qt::red); + myPen.setWidth(3); + myPen.setColor(myColor); painter->setPen(myPen); + + //Set brush attributes painter->setBrush(myColor); + //Create line from (0,0), to (1,1). Later, we'll scale and rotate it + QLineF line(0,0,1.0,1.0); + + //Set the starting point to (0,0) + line.setP1(QPointF(0,0)); + + //Set angle and length + line.setLength(60.0); + line.setAngle(90.0); + + //Form arrowhead double angle = ::acos(line.dx() / line.length()); if (line.dy() <= 0) angle = (Pi * 2) - angle; @@ -77,15 +95,89 @@ namespace mapcontrol cos(angle + Pi / 3) * arrowSize); QPointF arrowP2 = line.pointAt(1) + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, cos(angle + Pi - Pi / 3) * arrowSize); + + //Generate arrowhead arrowHead.clear(); arrowHead << line.pointAt(1) << arrowP1 << arrowP2; painter->drawPolygon(arrowHead); painter->setPen(myPen); painter->drawLine(line); + + //*********** Create trend arc + float radius; + + float spanAngle = yawRate_dps * 3; //Forecast 3 seconds into the future + + float meters2pixels=5; //This should be a function of the zoom level, and not a fixed constant + radius=fabs((groundspeed_kph/3.6)/(yawRate_dps*Pi/180))*meters2pixels; //Calculate radius in [m], and then convert to Px. +// qDebug()<< "Radius:" << radius; +// qDebug()<< "Span angle:" << spanAngle; + + //Set trend arc's color + myPen.setColor(Qt::magenta); + painter->setPen(myPen); + + //Draw arc. Qt is incomprehensibly limited in that it does not let you set a radius and two points, + //so instead it's a hackish approach requiring a rectangle and a span angle + if (spanAngle > 0){ + QRectF rect(0, -radius, radius*2, radius*2); + painter->drawArc(rect, 180*16, -spanAngle*16); + } + else{ + QRectF rect(-2*radius, -radius, radius*2, radius*2); + painter->drawArc(rect, 0*16, -spanAngle*16); + } + + //HUH? What does this do? painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); + + //***** Text info overlay. The font is a "glow" font, so that it's easier to use on the map + + //Rotate the text back to vertical qreal rot=this->rotation(); painter->rotate(-1*rot); - painter->drawText(QPointF(10,10),"KENZ"); + + //Define font + QFont borderfont( "Arial", 14, QFont::Normal, false ); + + //Top left corner of text + int textAnchorX = 20; + int textAnchorY = 20; + + //Create text lines + QString uavoInfoStrLine1, uavoInfoStrLine2; + QString uavoInfoStrLine3; + QString uavoInfoStrLine4; + + //For whatever reason, Qt does not let QPainterPath have text wrapping. So each line of + //text has to be added to a different line. + uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); + uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph)); + uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat()).arg(coord.Lng())); + uavoInfoStrLine4.append(QString("Altitude: %1 m").arg(this->altitude)); + + //Add the lines of text to the path + //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. + QPainterPath path; + path.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); + path.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); + path.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); + path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); + + //First pass is the outline... + myPen.setWidth(4); + myPen.setColor(Qt::black); + painter->setPen(myPen); + painter->setBrush(Qt::black); + painter->drawPath(path); + + //...second pass is the inlay + myPen.setWidth(1); + myPen.setColor(Qt::white); + painter->setBrush(Qt::white); + painter->setPen(myPen); + painter->drawPath(path); + } QRectF UAVItem::boundingRect()const @@ -93,6 +185,36 @@ namespace mapcontrol return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); } + void UAVItem::SetNED(double NED[3]){ + this->NED[0] = NED[0]; + this->NED[1] = NED[1]; + this->NED[2] = NED[2]; + } + + void UAVItem::SetYawRate(double yawRate_dps){ + this->yawRate_dps=yawRate_dps; + + //There is a minimum arc distance under which Qt no longer draws an arc. At this low a turning rate, + //all curves look straight, so the user won't notice the difference. Moreover, our sensors aren't + //accurate enough to reliably describe this low a yaw rate. + if (fabs(this->yawRate_dps) < 5e-1){ //This number is really the smallest we can go. Any smaller, and it might have problems if we forecast a shorter distance into the future + this->yawRate_dps=5e-1; + } + + } + + void UAVItem::SetCAS(double CAS_mps){ + this->CAS_mps=CAS_mps; + } + + void UAVItem::SetGroundspeed(double vNED[3]){ + this->vNED[0] = vNED[0]; + this->vNED[1] = vNED[1]; + this->vNED[2] = vNED[2]; + groundspeed_kph=sqrt(vNED[0]*vNED[0] + vNED[1]*vNED[1] + vNED[2]*vNED[2])*3.6; + } + + void UAVItem::SetUAVPos(const internals::PointLatLng &position, const int &altitude) { if(coord.IsEmpty()) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 972749869..1444afa5a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -57,6 +57,31 @@ namespace mapcontrol enum { Type = UserType + 2 }; UAVItem(MapGraphicItem* map,OPMapWidget* parent, QString uavPic=QString::fromUtf8(":/uavs/images/mapquad.png")); ~UAVItem(); + + /** + * @brief Sets the UAV NED position + * + * @param NED + */ + void SetNED(double NED[3]); + /** + * @brief Sets the UAV groundspeed + * + * @param NED + */ + void SetGroundspeed(double vNED[3]); + /** + * @brief Sets the UAV Calibrated Airspeed + * + * @param NED + */ + void SetCAS(double CAS); + /** + * @brief Sets the UAV yaw rate + * + * @param NED + */ + void SetYawRate(double yawRate_dps); /** * @brief Sets the UAV position * @@ -201,6 +226,11 @@ namespace mapcontrol UAVTrailType::Types trailtype; internals::PointLatLng coord; internals::PointLatLng lastcoord; + double NED[3]; + double vNED[3]; + double CAS_mps; + double groundspeed_kph; + double yawRate_dps; QPixmap pic; core::Point localposition; OPMapWidget* mapwidget; diff --git a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp index 66dbfd1d6..fcfeceb57 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp @@ -390,9 +390,10 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) //attRaw->setData(rawData); Gyros::DataFields gyroData; memset(&gyroData, 0, sizeof(Gyros::DataFields)); - gyroData.x = rollRate; - gyroData.y = pitchRate; - gyroData.z = yawRate; +#define Pi 3.141529654 + gyroData.x = rollRate*180/Pi; + gyroData.y = pitchRate*180/Pi; + gyroData.z = yawRate*180/Pi; gyros->setData(gyroData); Accels::DataFields accelData; @@ -420,7 +421,7 @@ void TraceBuf(const char* buf,int len) { if(i>0) { - qDebug() << str; +// qDebug() << str; str.clear(); reminder=false; } @@ -429,6 +430,7 @@ void TraceBuf(const char* buf,int len) str+=QString(" 0x%1").arg((quint8)buf[i],2,16,QLatin1Char('0')); } - if(reminder) - qDebug() << str; + if(reminder){ +// qDebug() << str; + } } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8f7351f1b..280773cc1 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -44,10 +44,18 @@ #include "utils/homelocationutil.h" #include "utils/worldmagmodel.h" +#include "../uavobjectwidgetutils/configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" #include "uavtalk/telemetrymanager.h" +#include "uavobject.h" +#include "uavobjectmanager.h" #include "positionactual.h" #include "homelocation.h" +#include "gpsposition.h" +#include "gyros.h" +#include "positionactual.h" +#include "velocityactual.h" #define allow_manual_home_location_move // ************************************************************************************* @@ -111,6 +119,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) obum = pm->getObject(); } + // ************** // get current location @@ -204,6 +213,9 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + + + if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position @@ -558,19 +570,45 @@ void OPMapGadgetWidget::updatePosition() uav_pos = internals::PointLatLng(uav_latitude, uav_longitude); // ************* - // get the current GPS details + // get the current GPS position and heading + GPSPosition *gpsPositionObj = GPSPosition::GetInstance(obm); + Q_ASSERT(gpsPositionObj); - // get current GPS position - if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude)) - return; + GPSPosition::DataFields gpsPositionData = gpsPositionObj->getData(); - // get current GPS heading -// gps_heading = getGPS_Heading(); - gps_heading = 0; + gps_heading = gpsPositionData.Heading; + gps_latitude = gpsPositionData.Latitude; + gps_longitude = gpsPositionData.Longitude; + gps_altitude = gpsPositionData.Altitude; + + qDebug() << "Lon: " << gps_longitude/1e7; gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); - // ************* + //********************** + // get the current position and heading estimates + PositionActual *positionActualObj = PositionActual::GetInstance(obm); + VelocityActual *velocityActualObj = VelocityActual::GetInstance(obm); + Gyros *gyrosObj = Gyros::GetInstance(obm); + + Q_ASSERT(positionActualObj); + Q_ASSERT(velocityActualObj); + Q_ASSERT(gyrosObj); + + PositionActual::DataFields positionActualData = positionActualObj->getData(); + VelocityActual::DataFields velocityActualData = velocityActualObj->getData(); + Gyros::DataFields gyrosData = gyrosObj->getData(); + + double NED[3]={positionActualData.North, positionActualData.East, positionActualData.Down}; + double vNED[3]={velocityActualData.North, velocityActualData.East, velocityActualData.Down}; + + //Set the position and heading estimates in the painter module + m_map->UAV->SetNED(NED); + m_map->UAV->SetCAS(-1); //THIS NEEDS TO BECOME AIRSPEED, ONCE WE SETTLE ON A UAVO + m_map->UAV->SetGroundspeed(vNED); + m_map->UAV->SetYawRate(gyrosData.z); //Not correct, but I'm being lazy right now. + + // ************* // display the UAV position QString str = From d30da01ca8301abce68ad0921e507ef704dcb60f Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Thu, 2 Aug 2012 11:36:36 +0200 Subject: [PATCH 058/116] Added additional message. Improved significant digit formatting. --- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 12 +++++++----- .../src/plugins/opmap/opmapgadgetwidget.cpp | 2 -- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 1aea4fc7d..797849914 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -146,15 +146,16 @@ namespace mapcontrol //Create text lines QString uavoInfoStrLine1, uavoInfoStrLine2; - QString uavoInfoStrLine3; - QString uavoInfoStrLine4; + QString uavoInfoStrLine3, uavoInfoStrLine4; + QString uavoInfoStrLine5; //For whatever reason, Qt does not let QPainterPath have text wrapping. So each line of //text has to be added to a different line. uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); - uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph)); - uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat()).arg(coord.Lng())); - uavoInfoStrLine4.append(QString("Altitude: %1 m").arg(this->altitude)); + uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1)); + uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7)); + uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); + uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); //Add the lines of text to the path //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. @@ -163,6 +164,7 @@ namespace mapcontrol path.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); path.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); + path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); //First pass is the outline... myPen.setWidth(4); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 280773cc1..fb2d39457 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -581,8 +581,6 @@ void OPMapGadgetWidget::updatePosition() gps_longitude = gpsPositionData.Longitude; gps_altitude = gpsPositionData.Altitude; - qDebug() << "Lon: " << gps_longitude/1e7; - gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); //********************** From e26e996734a0c96ee897e7a05f2add58975b7afb Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Thu, 2 Aug 2012 14:43:26 +0200 Subject: [PATCH 059/116] Added in time rings, using proper scaling. --- .../internals/projections/lks94projection.cpp | 3 + .../src/internals/pureprojection.cpp | 3 + .../opmapcontrol/src/mapwidget/uavitem.cpp | 59 ++++++++++++++++--- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 1 + 4 files changed, 59 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp index f476ba2f1..13e6f4fb4 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp @@ -614,6 +614,9 @@ double LKS94Projection::GetTileMatrixResolution(int const& zoom) return ret; } +/* + * Returns the conversion from pixels to meters + */ double LKS94Projection::GetGroundResolution(int const& zoom, double const& latitude) { Q_UNUSED(zoom); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 2f52aff6f..83893af6c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -103,6 +103,9 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) return ret; } + /* + * Returns the conversion from pixels to meters + */ double PureProjection::GetGroundResolution(const int &zoom,const double &latitude) { return (cos(latitude * (PI / 180)) * 2 * PI * Axis()) / GetTileMatrixSizePixel(zoom).Width(); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 797849914..5765be3ea 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -74,7 +74,7 @@ namespace mapcontrol painter->setPen(myPen); //Set brush attributes - painter->setBrush(myColor); +// painter->setBrush(myColor); //Create line from (0,0), to (1,1). Later, we'll scale and rotate it QLineF line(0,0,1.0,1.0); @@ -104,12 +104,20 @@ namespace mapcontrol painter->drawLine(line); //*********** Create trend arc - float radius; + double radius; + double spanAngle = yawRate_dps * 5; //Forecast 5 seconds into the future - float spanAngle = yawRate_dps * 3; //Forecast 3 seconds into the future - float meters2pixels=5; //This should be a function of the zoom level, and not a fixed constant - radius=fabs((groundspeed_kph/3.6)/(yawRate_dps*Pi/180))*meters2pixels; //Calculate radius in [m], and then convert to Px. + //Find the scale factor between meters and pixels + double pixels2meters = map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); + float meters2pixels=1.0 / pixels2meters; + + //Calculate radius in [m], and then convert to pixels in local frame (not the same frame as is displayed on the map widget) + double groundspeed_mps=groundspeed_kph/3.6; + radius=fabs(groundspeed_mps/(yawRate_dps*Pi/180))*meters2pixels; + + qDebug() << "Scale: " << meters2pixels; + qDebug() << "Zoom: " << map->ZoomTotal(); // qDebug()<< "Radius:" << radius; // qDebug()<< "Span angle:" << spanAngle; @@ -131,6 +139,28 @@ namespace mapcontrol //HUH? What does this do? painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); + + //*********** Create time rings + myPen.setWidth(2); + + double alpha= .1; + groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; + + double ringTime=10*pow(2,17-map->ZoomTotal()); + + myPen.setColor(QColor(0, 0, 0, 100)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*1*meters2pixels,groundspeed_mps_filt*ringTime*1*meters2pixels); + + myPen.setColor(QColor(0, 0, 0, 110)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*2*meters2pixels,groundspeed_mps_filt*ringTime*2*meters2pixels); + + myPen.setColor(QColor(0, 0, 0, 120)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*4*meters2pixels,groundspeed_mps_filt*ringTime*4*meters2pixels); + + //***** Text info overlay. The font is a "glow" font, so that it's easier to use on the map //Rotate the text back to vertical @@ -157,7 +187,7 @@ namespace mapcontrol uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); - //Add the lines of text to the path + //Add the uavo info text to the path //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. QPainterPath path; path.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); @@ -166,7 +196,22 @@ namespace mapcontrol path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); - //First pass is the outline... + //Add text for time rings. Always add the left side... + path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + //... and add the right side, only if it doesn't interfere with the uav info text + if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ + path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + } + path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + } + path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + } + + //Now draw the text. First pass is the outline... myPen.setWidth(4); myPen.setColor(Qt::black); painter->setPen(myPen); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 1444afa5a..a89ebc03e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -245,6 +245,7 @@ namespace mapcontrol bool autosetreached; double Distance3D(internals::PointLatLng const& coord, int const& altitude); double autosetdistance; + double groundspeed_mps_filt; // QRectF rect; public slots: From 3e4f2e21ce1729005a65339f16a5d2a1332053ac Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Thu, 2 Aug 2012 19:13:54 +0200 Subject: [PATCH 060/116] Added context menu for switching UAV text output off. --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 74 +++++++++++-------- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 3 + .../src/plugins/opmap/opmapgadgetwidget.cpp | 26 +++++-- .../src/plugins/opmap/opmapgadgetwidget.h | 2 + 4 files changed, 68 insertions(+), 37 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 5765be3ea..ee0633598 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -32,7 +32,7 @@ const qreal Pi = 3.14; namespace mapcontrol { UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100),altitude(0) + ,autosetdistance(100),altitude(0),showUAVInfo(false) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,true); @@ -60,6 +60,13 @@ namespace mapcontrol Q_UNUSED(widget); + //Draw plane + painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); + + //Return if context menu switch for UAV info is off + if(!showUAVInfo) + return; + QPen myPen; //Turn on anti-aliasing so the fonts don't look terrible @@ -136,30 +143,28 @@ namespace mapcontrol painter->drawArc(rect, 0*16, -spanAngle*16); } - //HUH? What does this do? - painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); - - //*********** Create time rings - myPen.setWidth(2); + double ringTime=0; + if(groundspeed_mps > 0){ //Don't clutter the display with rings that are only one pixel wide + myPen.setWidth(2); - double alpha= .1; - groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; + double alpha= .1; + groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; - double ringTime=10*pow(2,17-map->ZoomTotal()); + ringTime=10*pow(2,17-map->ZoomTotal()); - myPen.setColor(QColor(0, 0, 0, 100)); - painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*1*meters2pixels,groundspeed_mps_filt*ringTime*1*meters2pixels); + myPen.setColor(QColor(0, 0, 0, 100)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*1*meters2pixels,groundspeed_mps_filt*ringTime*1*meters2pixels); - myPen.setColor(QColor(0, 0, 0, 110)); - painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*2*meters2pixels,groundspeed_mps_filt*ringTime*2*meters2pixels); - - myPen.setColor(QColor(0, 0, 0, 120)); - painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*4*meters2pixels,groundspeed_mps_filt*ringTime*4*meters2pixels); + myPen.setColor(QColor(0, 0, 0, 110)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*2*meters2pixels,groundspeed_mps_filt*ringTime*2*meters2pixels); + myPen.setColor(QColor(0, 0, 0, 120)); + painter->setPen(myPen); + painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*4*meters2pixels,groundspeed_mps_filt*ringTime*4*meters2pixels); + } //***** Text info overlay. The font is a "glow" font, so that it's easier to use on the map @@ -196,19 +201,22 @@ namespace mapcontrol path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); - //Add text for time rings. Always add the left side... - path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); - //... and add the right side, only if it doesn't interfere with the uav info text - if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ - path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + //Add text for time rings. + if(groundspeed_mps > 0){ + //Always add the left side... + path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + //... and add the right side, only if it doesn't interfere with the uav info text + if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ + path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + } + path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); } - path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); } - path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); } //Now draw the text. First pass is the outline... @@ -414,4 +422,10 @@ namespace mapcontrol { pic.load(":/uavs/images/"+UAVPic); } + + void UAVItem::SetShowUAVInfo(bool const& value) + { + showUAVInfo=value; + } + } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index a89ebc03e..d960fa356 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -218,6 +218,8 @@ namespace mapcontrol int type() const; void SetUavPic(QString UAVPic); + void SetShowUAVInfo(bool const& value); + private: MapGraphicItem* map; QPolygonF arrowHead; @@ -246,6 +248,7 @@ namespace mapcontrol double Distance3D(internals::PointLatLng const& coord, int const& altitude); double autosetdistance; double groundspeed_mps_filt; + bool showUAVInfo; // QRectF rect; public slots: diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index fb2d39457..4856646a4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -44,8 +44,6 @@ #include "utils/homelocationutil.h" #include "utils/worldmagmodel.h" -#include "../uavobjectwidgetutils/configtaskwidget.h" -#include "extensionsystem/pluginmanager.h" #include "uavtalk/telemetrymanager.h" #include "uavobject.h" #include "uavobjectmanager.h" @@ -56,6 +54,7 @@ #include "gyros.h" #include "positionactual.h" #include "velocityactual.h" + #define allow_manual_home_location_move // ************************************************************************************* @@ -119,7 +118,6 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) obum = pm->getObject(); } - // ************** // get current location @@ -214,10 +212,8 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - - if(m_map->GPS) - m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the GPS position model=new flightDataModel(this); table=new pathPlanner(); @@ -427,6 +423,8 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) contextMenu.addAction(showDiagnostics); + contextMenu.addAction(showUAVInfo); + contextMenu.addSeparator()->setText(tr("Zoom")); contextMenu.addAction(zoomInAct); @@ -1247,6 +1245,12 @@ void OPMapGadgetWidget::createActions() showDiagnostics->setChecked(false); connect(showDiagnostics, SIGNAL(toggled(bool)), this, SLOT(onShowDiagnostics_toggled(bool))); + showUAVInfo = new QAction(tr("Show UAV Info"), this); + showUAVInfo->setStatusTip(tr("Show/Hide the UAV info")); + showUAVInfo->setCheckable(true); + showUAVInfo->setChecked(false); + connect(showUAVInfo, SIGNAL(toggled(bool)), this, SLOT(onShowUAVInfo_toggled(bool))); + showHomeAct = new QAction(tr("Show Home"), this); showHomeAct->setStatusTip(tr("Show/Hide the Home location")); showHomeAct->setCheckable(true); @@ -1539,12 +1543,20 @@ void OPMapGadgetWidget::onShowCompassAct_toggled(bool show) void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show) { - if (!m_widget || !m_map) + if (!m_widget || !m_map) return; m_map->SetShowDiagnostics(show); } +void OPMapGadgetWidget::onShowUAVInfo_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->SetShowUAVInfo(show); +} + void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) { if (!m_widget || !m_map) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 5d844fb57..65a93e6c0 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -174,6 +174,7 @@ private slots: void onCopyMouseLonToClipAct_triggered(); void onShowCompassAct_toggled(bool show); void onShowDiagnostics_toggled(bool show); + void onShowUAVInfo_toggled(bool show); void onShowUAVAct_toggled(bool show); void onShowHomeAct_toggled(bool show); void onShowTrailLineAct_toggled(bool show); @@ -244,6 +245,7 @@ private: QAction *copyMouseLonToClipAct; QAction *showCompassAct; QAction *showDiagnostics; + QAction *showUAVInfo; QAction *showHomeAct; QAction *showUAVAct; QAction *zoomInAct; From 3e23163dde8d934525ba0599a2ac91f6c0199f06 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Thu, 2 Aug 2012 20:21:29 +0200 Subject: [PATCH 061/116] Improved static and update behavior. --- .../libs/opmapcontrol/src/mapwidget/uavitem.cpp | 15 +++++++-------- .../src/libs/opmapcontrol/src/mapwidget/uavitem.h | 1 - .../src/plugins/opmap/opmapgadgetwidget.cpp | 1 + 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index ee0633598..3e937818a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -28,6 +28,7 @@ #include "uavitem.h" const qreal Pi = 3.14; +static double groundspeed_mps_filt; namespace mapcontrol { @@ -123,8 +124,8 @@ namespace mapcontrol double groundspeed_mps=groundspeed_kph/3.6; radius=fabs(groundspeed_mps/(yawRate_dps*Pi/180))*meters2pixels; - qDebug() << "Scale: " << meters2pixels; - qDebug() << "Zoom: " << map->ZoomTotal(); +// qDebug() << "Scale: " << meters2pixels; +// qDebug() << "Zoom: " << map->ZoomTotal(); // qDebug()<< "Radius:" << radius; // qDebug()<< "Span angle:" << spanAngle; @@ -144,15 +145,13 @@ namespace mapcontrol } //*********** Create time rings - double ringTime=0; + double ringTime=10*pow(2,17-map->ZoomTotal()); //Basic ring is 10 seconds wide at zoom level 17 + + double alpha= .05; + groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; if(groundspeed_mps > 0){ //Don't clutter the display with rings that are only one pixel wide myPen.setWidth(2); - double alpha= .1; - groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; - - ringTime=10*pow(2,17-map->ZoomTotal()); - myPen.setColor(QColor(0, 0, 0, 100)); painter->setPen(myPen); painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*1*meters2pixels,groundspeed_mps_filt*ringTime*1*meters2pixels); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index d960fa356..67ef23d65 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -247,7 +247,6 @@ namespace mapcontrol bool autosetreached; double Distance3D(internals::PointLatLng const& coord, int const& altitude); double autosetdistance; - double groundspeed_mps_filt; bool showUAVInfo; // QRectF rect; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 4856646a4..f4cdcc669 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1555,6 +1555,7 @@ void OPMapGadgetWidget::onShowUAVInfo_toggled(bool show) return; m_map->UAV->SetShowUAVInfo(show); + update(); } void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) From 74cd57e8a017e9120fa8d26c2766a7cc17447e31 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 7 Aug 2012 21:36:26 +0100 Subject: [PATCH 062/116] GCS - IFDEFed everything pathplanner related. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index f4cdcc669..2d01319ee 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -214,7 +214,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the GPS position - +#ifdef USE_PATHPLANNER model=new flightDataModel(this); table=new pathPlanner(); selectionModel=new QItemSelectionModel(model); @@ -224,7 +224,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) UAVProxy=new modelUavoProxy(this,model); connect(table,SIGNAL(sendPathPlanToUAV()),UAVProxy,SLOT(modelToObjects())); connect(table,SIGNAL(receivePathPlanFromUAV()),UAVProxy,SLOT(objectsToModel())); - +#endif magicWayPoint=m_map->magicWPCreate(); magicWayPoint->setVisible(false); @@ -481,7 +481,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) uav_menu.addAction(goUAVAct); // ********* - +#ifdef USE_PATHPLANNER switch (m_map_mode) { case Normal_MapMode: @@ -513,7 +513,7 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) contextMenu.addAction(homeMagicWaypointAct); break; } - +#endif // ********* QMenu overlaySubMenu(tr("&Overlay Opacity "),this); @@ -1318,7 +1318,7 @@ void OPMapGadgetWidget::createActions() TODO: Waypoint support is disabled for v1.0 */ - +#ifdef USE_PATHPLANNER wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); wayPointEditorAct->setShortcut(tr("Ctrl+W")); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); @@ -1355,7 +1355,7 @@ void OPMapGadgetWidget::createActions() clearWayPointsAct->setShortcut(tr("Ctrl+C")); clearWayPointsAct->setStatusTip(tr("Clear waypoints")); connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); - +#endif overlayOpacityActGroup = new QActionGroup(this); connect(overlayOpacityActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onOverlayOpacityActGroup_triggered(QAction *))); overlayOpacityAct.clear(); From 6b3cb29ea170479130def3a724468b89820cd944 Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Wed, 8 Aug 2012 20:56:29 +0200 Subject: [PATCH 063/116] Fixed maximum size for title bar in map widget. --- ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui b/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui index 5dc841482..ece39e353 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_widget.ui @@ -49,7 +49,7 @@ 16777215 - 16777215 + 40 From f3e1e768ad720b3410f86bb9f97ec2e23ab1f8e1 Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Wed, 8 Aug 2012 11:20:55 +0200 Subject: [PATCH 064/116] Refactored variable names to be more helpful. --- .../openpilotgcs/src/plugins/config/input.ui | 2 +- .../src/plugins/hitlnew/xplanesimulator.cpp | 24 +++++++++---------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 422904bb5..168e77938 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -385,7 +385,7 @@ margin:1px; - + Qt::Vertical diff --git a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp index fcfeceb57..1546b862e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp @@ -210,9 +210,9 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) float accX = 0; float accY = 0; float accZ = 0; - float rollRate=0; - float pitchRate=0; - float yawRate=0; + float rollRate_rad=0; + float pitchRate_rad=0; + float yawRate_rad=0; QString str; QByteArray& buf = const_cast(dataBuf); @@ -269,10 +269,10 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) velZ = *((float*)(buf.data()+4*5)); break; - case XplaneSimulator::AngularVelocities: - pitchRate = *((float*)(buf.data()+4*1)); - rollRate = *((float*)(buf.data()+4*2)); - yawRate = *((float*)(buf.data()+4*3)); + case XplaneSimulator::AngularVelocities: //In [rad/s] + pitchRate_rad = *((float*)(buf.data()+4*1)); + rollRate_rad = *((float*)(buf.data()+4*2)); + yawRate_rad = *((float*)(buf.data()+4*3)); break; case XplaneSimulator::Gload: @@ -380,8 +380,8 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) //memset(&rawData, 0, sizeof(AttitudeRaw::DataFields)); //rawData = attRaw->getData(); //rawData.gyros[0] = rollRate; - //rawData.gyros_filtered[1] = cos(DEG2RAD * roll) * pitchRate + sin(DEG2RAD * roll) * yawRate; - //rawData.gyros_filtered[2] = cos(DEG2RAD * roll) * yawRate - sin(DEG2RAD * roll) * pitchRate; + //rawData.gyros_filtered[1] = cos(DEG2RAD * roll) * pitchRate_rad + sin(DEG2RAD * roll) * yawRate_rad; + //rawData.gyros_filtered[2] = cos(DEG2RAD * roll) * yawRate_rad - sin(DEG2RAD * roll) * pitchRate_rad; //rawData.gyros[1] = pitchRate; //rawData.gyros[2] = yawRate; //rawData.accels[0] = accX; @@ -391,9 +391,9 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) Gyros::DataFields gyroData; memset(&gyroData, 0, sizeof(Gyros::DataFields)); #define Pi 3.141529654 - gyroData.x = rollRate*180/Pi; - gyroData.y = pitchRate*180/Pi; - gyroData.z = yawRate*180/Pi; + gyroData.x = rollRate_rad*180/Pi; + gyroData.y = pitchRate_rad*180/Pi; + gyroData.z = yawRate_rad*180/Pi; gyros->setData(gyroData); Accels::DataFields accelData; From fe6ea7e0e2fda6df56ca348134f293535f451129 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Wed, 8 Aug 2012 18:20:15 +0200 Subject: [PATCH 065/116] Fixed getUAVPosition to use position actual data correctly. Refactored coordinate conversion names in order to be clearer, since two identically named functions-- one in revo, one here-- performed very different maths. --- .../src/libs/utils/coordinateconversions.cpp | 32 +++++++++-- .../src/libs/utils/coordinateconversions.h | 3 +- .../src/plugins/hitlnew/il2simulator.cpp | 2 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 53 ++++++++----------- 4 files changed, 51 insertions(+), 39 deletions(-) diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp index ba67d8ab5..a7f7117b1 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp @@ -121,19 +121,18 @@ int CoordinateConversions::ECEF2LLA(double ECEF[3], double LLA[3]) } /** - * Get the current location in Longitude, Latitude Altitude (above WSG-48 ellipsoid) - * @param[in] BaseECEF the ECEF of the home location (in cm) + * Get the current location in Longitude, Latitude Altitude (above WSG-84 ellipsoid) + * @param[in] BaseECEF the ECEF of the home location (in m) * @param[in] NED the offset from the home location (in m) - * @param[out] position three element double for position in degrees and meters + * @param[out] position three element double for position in decimal degrees and altitude in meters * @returns * @arg 0 success * @arg -1 for failure */ -int CoordinateConversions::GetLLA(double BaseECEFcm[3], double NED[3], double position[3]) +int CoordinateConversions::NED2LLA_HomeECEF(double BaseECEFm[3], double NED[3], double position[3]) { int i; // stored value is in cm, convert to m - double BaseECEFm[3] = {BaseECEFcm[0], BaseECEFcm[1], BaseECEFcm[2]}; double BaseLLA[3]; double ECEF[3]; double Rne [3][3]; @@ -151,6 +150,29 @@ int CoordinateConversions::GetLLA(double BaseECEFcm[3], double NED[3], double po return 0; } +/** + * Get the current location in Longitude, Latitude, Altitude (above WSG-84 ellipsoid) + * @param[in] homeLLA the latitude, longitude, and altitude of the home location (in [m]) + * @param[in] NED the offset from the home location (in [m]) + * @param[out] position three element double for position in decimal degrees and altitude in meters + * @returns + * @arg 0 success + * @arg -1 for failure + */ +int CoordinateConversions::NED2LLA_HomeLLA(double homeLLA[3], double NED[3], double position[3]) +{ + double T[3]; + T[0] = homeLLA[2]+6.378137E6f * M_PI / 180.0; + T[1] = cosf(homeLLA[0] * M_PI / 180.0)*(homeLLA[2]+6.378137E6f) * M_PI / 180.0; + T[2] = -1.0f; + + position[0] = homeLLA[0] + NED[0] / T[0]; + position[1] = homeLLA[1] + NED[1] / T[1]; + position[2] = homeLLA[2] + NED[2] / T[2]; + + return 0; +} + void CoordinateConversions::LLA2Base(double LLA[3], double BaseECEF[3], float Rne[3][3], float NED[3]) { double ECEF[3]; diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h index f6f47a8d7..ca077a0c4 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h @@ -41,7 +41,8 @@ class QTCREATOR_UTILS_EXPORT CoordinateConversions { public: CoordinateConversions(); - int GetLLA(double LLA[3], double NED[3], double position[3]); + int NED2LLA_HomeECEF(double BaseECEFcm[3], double NED[3], double position[3]); + int NED2LLA_HomeLLA(double LLA[3], double NED[3], double position[3]); void RneFromLLA(double LLA[3], double Rne[3][3]); void LLA2ECEF(double LLA[3], double ECEF[3]); int ECEF2LLA(double ECEF[3], double LLA[3]); diff --git a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp index 78f78ffac..f61feb9cf 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp @@ -333,7 +333,7 @@ void IL2Simulator::processUpdate(const QByteArray& inp) NED[0] = current.Y; NED[1] = current.X; NED[2] = -current.Z; - Utils::CoordinateConversions().GetLLA(ECEF,NED,LLA); + Utils::CoordinateConversions().NED2LLA_HomeECEF(ECEF,NED,LLA); gpsData.Latitude = LLA[0] * 10e6; gpsData.Longitude = LLA[1] * 10e6; gpsData.Satellites = 7; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 2d01319ee..96aca68c5 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2017,54 +2017,43 @@ internals::PointLatLng OPMapGadgetWidget::destPoint(internals::PointLatLng sourc bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, double &altitude) { - double BaseECEF[3]; double NED[3]; double LLA[3]; - UAVObject *obj; + double homeLLA[3]; - if (!obm) - return false; + Q_ASSERT(obm != NULL); - obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); - if (!obj) return false; - BaseECEF[0] = obj->getField(QString("ECEF"))->getDouble(0) / 100; - BaseECEF[1] = obj->getField(QString("ECEF"))->getDouble(1) / 100; - BaseECEF[2] = obj->getField(QString("ECEF"))->getDouble(2) / 100; + HomeLocation *homeLocation = HomeLocation::GetInstance(obm); + Q_ASSERT(homeLocation != NULL); + HomeLocation::DataFields homeLocationData = homeLocation->getData(); - obj = dynamic_cast(obm->getObject(QString("PositionActual"))); - if (!obj) return false; - NED[0] = obj->getField(QString("North"))->getDouble() / 100; - NED[1] = obj->getField(QString("East"))->getDouble() / 100; - NED[2] = obj->getField(QString("Down"))->getDouble() / 100; + homeLLA[0] = homeLocationData.Latitude / 1e7; + homeLLA[1] = homeLocationData.Longitude / 1e7; + homeLLA[2] = homeLocationData.Altitude; -// obj = dynamic_cast(om->getObject(QString("PositionDesired"))); + PositionActual *positionActual = PositionActual::GetInstance(obm); + Q_ASSERT(positionActual != NULL); + PositionActual::DataFields positionActualData = positionActual->getData(); -// obj = dynamic_cast(objManager->getObject("VelocityActual")); // air speed + NED[0] = positionActualData.North; + NED[1] = positionActualData.East; + NED[2] = positionActualData.Down; - Utils::CoordinateConversions().GetLLA(BaseECEF, NED, LLA); + Utils::CoordinateConversions().NED2LLA_HomeLLA(homeLLA, NED, LLA); latitude = LLA[0]; longitude = LLA[1]; altitude = LLA[2]; + qDebug()<< " " << latitude << " " << longitude << " " << altitude; + if (latitude != latitude) latitude = 0; // nan detection -// if (isNan(latitude)) latitude = 0; // nan detection - else -// if (!isFinite(latitude)) latitude = 0; -// else - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; + else if (latitude > 90) latitude = 90; + else if (latitude < -90) latitude = -90; if (longitude != longitude) longitude = 0; // nan detection - else -// if (longitude > std::numeric_limits::max()) longitude = 0; // +infinite -// else -// if (longitude < -std::numeric_limits::max()) longitude = 0; // -infinite -// else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; + else if (longitude > 180) longitude = 180; + else if (longitude < -180) longitude = -180; if (altitude != altitude) altitude = 0; // nan detection From 619b4ffa8c45a05a7dc0798495b830a28180c625 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 11 Aug 2012 19:58:14 +0100 Subject: [PATCH 066/116] GCS-Prevent the map from being dragged beyond the available imagery. Previous way seemed broken, looked ugly and like a bug. --- .../libs/opmapcontrol/src/internals/core.cpp | 17 ++++++++++++++++- .../src/libs/opmapcontrol/src/internals/core.h | 3 ++- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp index 8a3fafc05..275f8b965 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp @@ -251,6 +251,7 @@ namespace internals { Matrix.Clear(); GoToCurrentPositionOnZoom(); UpdateBounds(); + keepInBounds(); emit OnMapDrag(); emit OnMapZoomChanged(); emit OnNeedInvalidation(); @@ -572,7 +573,7 @@ namespace internals { { renderOffset.SetX(pt.X() - dragPoint.X()); renderOffset.SetY(pt.Y() - dragPoint.Y()); - + keepInBounds(); UpdateCenterTileXYLocation(); if(centerTileXYLocation != centerTileXYLocationLast) @@ -692,4 +693,18 @@ namespace internals { pxRes1000km = (int) (1000000.0 / rez); // 1000km pxRes5000km = (int) (5000000.0 / rez); // 5000km } + void Core::keepInBounds() + { + if(renderOffset.X()>0) + renderOffset.SetX(0); + if(renderOffset.Y()>0) + renderOffset.SetY(0); + int maxDragY=GetCurrentRegion().Height()-GettileRect().Height()*(maxOfTiles.Height()-minOfTiles.Height()+1); + int maxDragX=GetCurrentRegion().Width()-GettileRect().Width()*(maxOfTiles.Width()-minOfTiles.Width()+1); + + if(maxDragY>renderOffset.Y()) + renderOffset.SetY(maxDragY); + if(maxDragX>renderOffset.X()) + renderOffset.SetX(maxDragX); + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h index 73c652de5..2bb2f3134 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h @@ -193,6 +193,7 @@ namespace internals { bool isStarted(){return started;} diagnostics GetDiagnostics(); + signals: void OnCurrentPositionChanged(internals::PointLatLng point); void OnTileLoadComplete(); @@ -206,7 +207,7 @@ namespace internals { private: - + void keepInBounds(); PointLatLng currentPosition; core::Point currentPositionPixel; core::Point renderOffset; From 1a22eef491de86be8398ede9772127ea3597da7d Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 11 Aug 2012 23:36:00 +0100 Subject: [PATCH 067/116] GCS-Several changes according to review comments --- .../src/internals/pureprojection.cpp | 8 +-- .../opmapcontrol/src/mapwidget/gpsitem.cpp | 50 ++----------------- .../src/mapwidget/opmapwidget.cpp | 34 +++++++------ .../opmapcontrol/src/mapwidget/trailitem.cpp | 1 - .../src/mapwidget/traillineitem.h | 2 - .../opmapcontrol/src/mapwidget/uavitem.cpp | 20 ++++---- .../src/mapwidget/waypointcircle.cpp | 19 ++++--- .../src/mapwidget/waypointitem.cpp | 3 -- .../src/mapwidget/waypointline.cpp | 11 ++-- .../src/plugins/opmap/opmapgadgetwidget.cpp | 11 ++-- 10 files changed, 57 insertions(+), 102 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 83893af6c..94c452936 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -221,10 +221,10 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) { - double lon1=p1.Lng()* (M_PI / 180);; - double lat1=p1.Lat()* (M_PI / 180);; - double lon2=p2.Lng()* (M_PI / 180);; - double lat2=p2.Lat()* (M_PI / 180);; + double lon1=p1.Lng()* (M_PI / 180); + double lat1=p1.Lat()* (M_PI / 180); + double lon2=p2.Lng()* (M_PI / 180); + double lat2=p2.Lat()* (M_PI / 180); return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2), cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*M_PI); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index aeb9055c3..48afa7fbd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -37,9 +37,9 @@ namespace mapcontrol localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); - trail=new QGraphicsItemGroup(); + trail=new QGraphicsItemGroup(this); trail->setParentItem(map); - trailLine=new QGraphicsItemGroup(); + trailLine=new QGraphicsItemGroup(this); trailLine->setParentItem(map); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); mapfollowtype=UAVMapFollowType::None; @@ -48,16 +48,14 @@ namespace mapcontrol } GPSItem::~GPSItem() { - delete trail; + } void GPSItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) { Q_UNUSED(option); Q_UNUSED(widget); - // painter->rotate(-90); painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); - // painter->drawRect(QRectF(-pic.width()/2,-pic.height()/2,pic.width()-1,pic.height()-1)); } QRectF GPSItem::boundingRect()const { @@ -97,48 +95,6 @@ namespace mapcontrol coord=position; this->altitude=altitude; RefreshPos(); - /*if(mapfollowtype==UAVMapFollowType::CenterAndRotateMap||mapfollowtype==UAVMapFollowType::CenterMap) - { - mapwidget->SetCurrentPosition(coord); - }*/ - this->update(); - /*if(autosetreached) - { - foreach(QGraphicsItem* i,map->childItems()) - { - WayPointItem* wp=qgraphicsitem_cast(i); - if(wp) - { - if(Distance3D(wp->Coord(),wp->Altitude())SetReached(true); - emit UAVReachedWayPoint(wp->Number(),wp); - } - } - } - } - if(mapwidget->Home!=0) - { - //verify if the UAV is inside the safety bouble - if(Distance3D(mapwidget->Home->Coord(),mapwidget->Home->Altitude())>mapwidget->Home->SafeArea()) - { - if(mapwidget->Home->safe!=false) - { - mapwidget->Home->safe=false; - mapwidget->Home->update(); - emit UAVLeftSafetyBouble(this->coord); - } - } - else - { - if(mapwidget->Home->safe!=true) - { - mapwidget->Home->safe=true; - mapwidget->Home->update(); - } - } - - }*/ } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 2d5426578..54cc1e575 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -33,7 +33,8 @@ namespace mapcontrol { - OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0),followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0) + OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0) + ,followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0),overlayOpacity(1) { setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); core=new internals::Core; @@ -59,7 +60,6 @@ namespace mapcontrol SetShowDiagnostics(showDiag); this->setMouseTracking(followmouse); SetShowCompass(true); - overlayOpacity=1; } void OPMapWidget::SetShowDiagnostics(bool const& value) @@ -111,7 +111,7 @@ namespace mapcontrol if(!from|!to) return NULL; WayPointLine* ret= new WayPointLine(from,to,map,color); - setOverlayOpacity(overlayOpacity); + ret->setOpacity(overlayOpacity); return ret; } WayPointLine * OPMapWidget::WPLineCreate(HomeItem *from, WayPointItem *to,QColor color) @@ -119,7 +119,7 @@ namespace mapcontrol if(!from|!to) return NULL; WayPointLine* ret= new WayPointLine(from,to,map,color); - setOverlayOpacity(overlayOpacity); + ret->setOpacity(overlayOpacity); return ret; } WayPointCircle * OPMapWidget::WPCircleCreate(WayPointItem *center, WayPointItem *radius, bool clockwise,QColor color) @@ -127,7 +127,7 @@ namespace mapcontrol if(!center|!radius) return NULL; WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color); - setOverlayOpacity(overlayOpacity); + ret->setOpacity(overlayOpacity); return ret; } @@ -136,7 +136,7 @@ namespace mapcontrol if(!center|!radius) return NULL; WayPointCircle* ret= new WayPointCircle(center,radius,clockwise,map,color); - setOverlayOpacity(overlayOpacity); + ret->setOpacity(overlayOpacity); return ret; } void OPMapWidget::SetShowUAV(const bool &value) @@ -147,14 +147,14 @@ namespace mapcontrol UAV->setParentItem(map); connect(this,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng)),UAV,SIGNAL(UAVLeftSafetyBouble(internals::PointLatLng))); connect(this,SIGNAL(UAVReachedWayPoint(int,WayPointItem*)),UAV,SIGNAL(UAVReachedWayPoint(int,WayPointItem*))); - setOverlayOpacity(overlayOpacity); + UAV->setOpacity(overlayOpacity); } else if(!value) { if(UAV!=0) { delete UAV; - UAV=0; + UAV=NULL; } } @@ -186,14 +186,20 @@ namespace mapcontrol } OPMapWidget::~OPMapWidget() { - delete UAV; - delete Home; - delete map; - delete core; - delete configuration; + if(UAV) + delete UAV; + if(Home) + delete Home; + if(map) + delete map; + if(core) + delete core; + if(configuration) + delete configuration; foreach(QGraphicsItem* i,this->items()) { - delete i; + if(i) + delete i; } } void OPMapWidget::closeEvent(QCloseEvent *event) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp index 41e50c29b..c9666dff9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp @@ -38,7 +38,6 @@ namespace mapcontrol void TrailItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) { - // painter->drawRect(QRectF(-3,-3,6,6)); painter->setBrush(m_brush); painter->drawEllipse(-2,-2,4,4); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h index f749e51bd..f5e7ec627 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h @@ -44,8 +44,6 @@ namespace mapcontrol enum { Type = UserType + 7 }; TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, QGraphicsItem* parent); int type() const; - // void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, - // QWidget *widget); internals::PointLatLng coord1; internals::PointLatLng coord2; private: diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 3e937818a..baaf8b24a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -26,8 +26,8 @@ */ #include "../internals/pureprojection.h" #include "uavitem.h" +#include -const qreal Pi = 3.14; static double groundspeed_mps_filt; namespace mapcontrol @@ -41,9 +41,9 @@ namespace mapcontrol localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); - trail=new QGraphicsItemGroup(); + trail=new QGraphicsItemGroup(this); trail->setParentItem(map); - trailLine=new QGraphicsItemGroup(); + trailLine=new QGraphicsItemGroup(this); trailLine->setParentItem(map); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); mapfollowtype=UAVMapFollowType::None; @@ -52,7 +52,7 @@ namespace mapcontrol } UAVItem::~UAVItem() { - delete trail; + } void UAVItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) @@ -97,12 +97,12 @@ namespace mapcontrol //Form arrowhead double angle = ::acos(line.dx() / line.length()); if (line.dy() <= 0) - angle = (Pi * 2) - angle; + angle = (M_PI * 2) - angle; - QPointF arrowP1 = line.pointAt(1) + QPointF(sin(angle + Pi / 3) * arrowSize, - cos(angle + Pi / 3) * arrowSize); - QPointF arrowP2 = line.pointAt(1) + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, - cos(angle + Pi - Pi / 3) * arrowSize); + QPointF arrowP1 = line.pointAt(1) + QPointF(sin(angle + M_PI / 3) * arrowSize, + cos(angle + M_PI / 3) * arrowSize); + QPointF arrowP2 = line.pointAt(1) + QPointF(sin(angle + M_PI - M_PI / 3) * arrowSize, + cos(angle + M_PI - M_PI / 3) * arrowSize); //Generate arrowhead arrowHead.clear(); @@ -122,7 +122,7 @@ namespace mapcontrol //Calculate radius in [m], and then convert to pixels in local frame (not the same frame as is displayed on the map widget) double groundspeed_mps=groundspeed_kph/3.6; - radius=fabs(groundspeed_mps/(yawRate_dps*Pi/180))*meters2pixels; + radius=fabs(groundspeed_mps/(yawRate_dps*M_PI/180))*meters2pixels; // qDebug() << "Scale: " << meters2pixels; // qDebug() << "Zoom: " << map->ZoomTotal(); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index aa66bb45d..c6dfac384 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -27,7 +27,6 @@ #include "waypointcircle.h" #include #include "homeitem.h" -const qreal Pi = 3.14; namespace mapcontrol { @@ -71,17 +70,17 @@ void WayPointCircle::paint(QPainter *painter, const QStyleOptionGraphicsItem *op painter->setBrush(myColor); double angle =0; if(!myClockWise) - angle+=Pi; + angle+=M_PI; - QPointF arrowP1 = p1 + QPointF(sin(angle + Pi / 3) * arrowSize, - cos(angle + Pi / 3) * arrowSize); - QPointF arrowP2 = p1 + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, - cos(angle + Pi - Pi / 3) * arrowSize); + QPointF arrowP1 = p1 + QPointF(sin(angle + M_PI / 3) * arrowSize, + cos(angle + M_PI / 3) * arrowSize); + QPointF arrowP2 = p1 + QPointF(sin(angle + M_PI - M_PI / 3) * arrowSize, + cos(angle + M_PI - M_PI / 3) * arrowSize); - QPointF arrowP21 = p2 + QPointF(sin(angle + Pi + Pi / 3) * arrowSize, - cos(angle + Pi + Pi / 3) * arrowSize); - QPointF arrowP22 = p2 + QPointF(sin(angle + Pi + Pi - Pi / 3) * arrowSize, - cos(angle + Pi + Pi - Pi / 3) * arrowSize); + QPointF arrowP21 = p2 + QPointF(sin(angle + M_PI + M_PI / 3) * arrowSize, + cos(angle + M_PI + M_PI / 3) * arrowSize); + QPointF arrowP22 = p2 + QPointF(sin(angle + M_PI + M_PI - M_PI / 3) * arrowSize, + cos(angle + M_PI + M_PI - M_PI / 3) * arrowSize); arrowHead.clear(); arrowHead << p1 << arrowP1 << arrowP2; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 929ffa0c9..8c7491fe5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -277,11 +277,9 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals void WayPointItem::setRelativeCoord(distBearingAltitude value) { - qDebug()<<"SetRelative("<update(); - qDebug()<<"setRelativeCoord EXIT"; } void WayPointItem::SetCoord(const internals::PointLatLng &value) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 748c4ca1d..7ba3072db 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -27,7 +27,6 @@ #include "waypointline.h" #include #include "homeitem.h" -const qreal Pi = 3.14; namespace mapcontrol { @@ -83,12 +82,12 @@ void WayPointLine::paint(QPainter *painter, const QStyleOptionGraphicsItem *opti double angle = ::acos(line().dx() / line().length()); if (line().dy() >= 0) - angle = (Pi * 2) - angle; + angle = (M_PI * 2) - angle; - QPointF arrowP1 = line().pointAt(0.5) + QPointF(sin(angle + Pi / 3) * arrowSize, - cos(angle + Pi / 3) * arrowSize); - QPointF arrowP2 = line().pointAt(0.5) + QPointF(sin(angle + Pi - Pi / 3) * arrowSize, - cos(angle + Pi - Pi / 3) * arrowSize); + QPointF arrowP1 = line().pointAt(0.5) + QPointF(sin(angle + M_PI / 3) * arrowSize, + cos(angle + M_PI / 3) * arrowSize); + QPointF arrowP2 = line().pointAt(0.5) + QPointF(sin(angle + M_PI - M_PI / 3) * arrowSize, + cos(angle + M_PI - M_PI / 3) * arrowSize); arrowHead.clear(); arrowHead << line().pointAt(0.5) << arrowP1 << arrowP2; painter->drawPolygon(arrowHead); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 96aca68c5..bcc1de88b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1572,7 +1572,8 @@ void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) return; m_map->UAV->setVisible(show); - m_map->GPS->setVisible(show); + if(m_map->GPS) + m_map->GPS->setVisible(show); } void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) @@ -1581,7 +1582,8 @@ void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) return; m_map->UAV->SetShowTrail(show); - m_map->GPS->SetShowTrail(show); + if(m_map->GPS) + m_map->GPS->SetShowTrail(show); } void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) @@ -1590,7 +1592,8 @@ void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) return; m_map->UAV->SetShowTrailLine(show); - m_map->GPS->SetShowTrailLine(show); + if(m_map->GPS) + m_map->GPS->SetShowTrailLine(show); } void OPMapGadgetWidget::onMapModeActGroup_triggered(QAction *action) @@ -2045,8 +2048,6 @@ bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, doub longitude = LLA[1]; altitude = LLA[2]; - qDebug()<< " " << latitude << " " << longitude << " " << altitude; - if (latitude != latitude) latitude = 0; // nan detection else if (latitude > 90) latitude = 90; else if (latitude < -90) latitude = -90; From 63c167c18333b05054f5bd77813ddb092725c14d Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 18:46:45 -0400 Subject: [PATCH 068/116] taskinfo: also track Event thread's stack usage and CPU utilization The event dispatcher thread is started differently than most other threads so it was missed in the taskinfo tracking information. Now it's also included. --- flight/UAVObjects/eventdispatcher.c | 3 +++ shared/uavobjectdefinition/taskinfo.xml | 6 +++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/flight/UAVObjects/eventdispatcher.c b/flight/UAVObjects/eventdispatcher.c index a5a728b62..e0ffbc99a 100644 --- a/flight/UAVObjects/eventdispatcher.c +++ b/flight/UAVObjects/eventdispatcher.c @@ -280,6 +280,9 @@ static void eventTask() int32_t delayMs; EventCallbackInfo evInfo; + /* Must do this in task context to ensure that TaskMonitor has already finished its init */ + TaskMonitorAdd(TASKINFO_RUNNING_EVENTDISPATCHER, eventTaskHandle); + // Initialize time timeToNextUpdateMs = xTaskGetTickCount()*portTICK_RATE_MS; diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 40f0d4bdf..551167501 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + + From 29ab1d8cf300033e53bfeca10042badf0c2f5d92 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 11 Aug 2012 19:46:00 -0400 Subject: [PATCH 069/116] actuator: factor out settings updates from main loop --- flight/Modules/Actuator/actuator.c | 229 ++++++++++++++------------- flight/PiOS.posix/inc/pios_servo.h | 2 +- flight/PiOS.posix/posix/pios_servo.c | 2 +- flight/PiOS.win32/win32/pios_servo.c | 2 +- flight/PiOS/STM32F10x/pios_servo.c | 2 +- flight/PiOS/STM32F4xx/pios_servo.c | 2 +- flight/PiOS/inc/pios_servo.h | 2 +- 7 files changed, 123 insertions(+), 118 deletions(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 775b71360..e59d50957 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -65,24 +65,25 @@ static xQueueHandle queue; static xTaskHandle taskHandle; static float lastResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; -static float lastFilteredResult[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; static float filterAccumulator[MAX_MIX_ACTUATORS]={0,0,0,0,0,0,0,0}; // used to inform the actuator thread that actuator update rate is changed -static uint8_t updateRateChanged = 0; +static volatile bool actuator_settings_updated; +// used to inform the actuator thread that mixer settings are changed +static volatile bool mixer_settings_updated; // Private functions static void actuatorTask(void* parameters); -static void actuator_update_rate(UAVObjEvent *); static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral); -static void setFailsafe(); +static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings); static float MixerCurve(const float throttle, const float* curve, uint8_t elements); -static bool set_channel(uint8_t mixer_channel, uint16_t value); -static void change_update_rate(); +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings); +static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update); +static void MixerSettingsUpdatedCb(UAVObjEvent * ev); +static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev); float ProcessMixer(const int index, const float curve1, const float curve2, - MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, + const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period); -static uint16_t lastChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM] = {0,0,0,0}; //this structure is equivalent to the UAVObjects for one mixer. typedef struct { uint8_t type; @@ -109,22 +110,26 @@ int32_t ActuatorStart() */ int32_t ActuatorInitialize() { - // Create object queue - queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); - + // Register for notification of changes to ActuatorSettings ActuatorSettingsInitialize(); - ActuatorDesiredInitialize(); - MixerSettingsInitialize(); - ActuatorCommandInitialize(); -#if defined(DIAGNOSTICS) - MixerStatusInitialize(); -#endif + ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb); - // Listen for ExampleObject1 updates + // Register for notification of changes to MixerSettings + MixerSettingsInitialize(); + MixerSettingsConnectCallback(MixerSettingsUpdatedCb); + + // Listen for ActuatorDesired updates (Primary input to this module) + ActuatorDesiredInitialize(); + queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); ActuatorDesiredConnectQueue(queue); - // If settings change, update the output rate - ActuatorSettingsConnectCallback(actuator_update_rate); + // Primary output of this module + ActuatorCommandInitialize(); + +#if defined(DIAGNOSTICS) + // UAVO only used for inspecting the internal status of the mixer during debug + MixerStatusInitialize(); +#endif return 0; } @@ -151,22 +156,25 @@ static void actuatorTask(void* parameters) float dT = 0.0f; ActuatorCommandData command; - MixerSettingsData mixerSettings; ActuatorDesiredData desired; MixerStatusData mixerStatus; FlightStatusData flightStatus; - uint8_t MotorsSpinWhileArmed; - int16_t ChannelMax[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM]; + /* Read initial values of ActuatorSettings */ + ActuatorSettingsData actuatorSettings; + actuator_settings_updated = false; + ActuatorSettingsGet(&actuatorSettings); - change_update_rate(); - - float * status = (float *)&mixerStatus; //access status objects as an array of floats + /* Read initial values of MixerSettings */ + MixerSettingsData mixerSettings; + mixer_settings_updated = false; + MixerSettingsGet(&mixerSettings); + + /* Force an initial configuration of the actuator update rates */ + actuator_update_rate_if_changed(&actuatorSettings, true); // Go to the neutral (failsafe) values until an ActuatorDesired update is received - setFailsafe(); + setFailsafe(&actuatorSettings, &mixerSettings); // Main task loop lastSysTime = xTaskGetTickCount(); @@ -174,19 +182,26 @@ static void actuatorTask(void* parameters) { PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR); - // Wait until the ActuatorDesired object is updated, if a timeout then go to failsafe - if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE ) - { - setFailsafe(); + // Wait until the ActuatorDesired object is updated + uint8_t rc = xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS); + + /* Process settings updated events even in timeout case so we always act on the latest settings */ + if (actuator_settings_updated) { + actuator_settings_updated = false; + ActuatorSettingsGet (&actuatorSettings); + actuator_update_rate_if_changed (&actuatorSettings, false); + } + if (mixer_settings_updated) { + mixer_settings_updated = false; + MixerSettingsGet (&mixerSettings); + } + + if (rc != pdTRUE) { + /* Update of ActuatorDesired timed out. Go to failsafe */ + setFailsafe(&actuatorSettings, &mixerSettings); continue; } - if(updateRateChanged!=0) - { - change_update_rate(); - updateRateChanged=0; - } - // Check how long since last update thisSysTime = xTaskGetTickCount(); if(thisSysTime > lastSysTime) // reuse dt in case of wraparound @@ -194,18 +209,12 @@ static void actuatorTask(void* parameters) lastSysTime = thisSysTime; FlightStatusGet(&flightStatus); - MixerSettingsGet (&mixerSettings); ActuatorDesiredGet(&desired); ActuatorCommandGet(&command); #if defined(DIAGNOSTICS) MixerStatusGet(&mixerStatus); #endif - ActuatorSettingsMotorsSpinWhileArmedGet(&MotorsSpinWhileArmed); - ActuatorSettingsChannelMaxGet(ChannelMax); - ActuatorSettingsChannelMinGet(ChannelMin); - ActuatorSettingsChannelNeutralGet(ChannelNeutral); - int nMixers = 0; Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type; for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) @@ -217,7 +226,7 @@ static void actuatorTask(void* parameters) } if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers. { - setFailsafe(); // So that channels like PWM buzzer keep working + setFailsafe(&actuatorSettings, &mixerSettings); // So that channels like PWM buzzer keep working continue; } @@ -225,7 +234,7 @@ static void actuatorTask(void* parameters) bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED; bool positiveThrottle = desired.Throttle >= 0.00f; - bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; + bool spinWhileArmed = actuatorSettings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM); @@ -264,6 +273,8 @@ static void actuatorTask(void* parameters) break; } + float * status = (float *)&mixerStatus; //access status objects as an array of floats + for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) { if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) { @@ -337,9 +348,9 @@ static void actuatorTask(void* parameters) for(int i = 0; i < MAX_MIX_ACTUATORS; i++) command.Channel[i] = scaleChannel(status[i], - ChannelMax[i], - ChannelMin[i], - ChannelNeutral[i]); + actuatorSettings.ChannelMax[i], + actuatorSettings.ChannelMin[i], + actuatorSettings.ChannelNeutral[i]); // Store update time command.UpdateTime = 1000.0f*dT; @@ -361,7 +372,7 @@ static void actuatorTask(void* parameters) for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { - success &= set_channel(n, command.Channel[n]); + success &= set_channel(n, command.Channel[n], &actuatorSettings); } if(!success) { @@ -379,15 +390,18 @@ static void actuatorTask(void* parameters) *Process mixing for one actuator */ float ProcessMixer(const int index, const float curve1, const float curve2, - MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period) + const MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, const float period) { - Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects - Mixer_t * mixer = &mixers[index]; + static float lastFilteredResult[MAX_MIX_ACTUATORS]; + const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects + const Mixer_t * mixer = &mixers[index]; + float result = (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE1] / 128.0f) * curve1) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + - (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_THROTTLECURVE2] / 128.0f) * curve2) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_ROLL] / 128.0f) * desired->Roll) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_PITCH] / 128.0f) * desired->Pitch) + + (((float)mixer->matrix[MIXERSETTINGS_MIXER1VECTOR_YAW] / 128.0f) * desired->Yaw); + if(mixer->type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { if(result < 0.0f) //idle throttle @@ -501,19 +515,13 @@ static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutr /** * Set actuator output to the neutral values (failsafe) */ -static void setFailsafe() +static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings) { - /* grab only the modules parts that we are going to use */ - int16_t ChannelMin[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - ActuatorSettingsChannelMinGet(ChannelMin); - int16_t ChannelNeutral[ACTUATORCOMMAND_CHANNEL_NUMELEM]; - ActuatorSettingsChannelNeutralGet(ChannelNeutral); + /* grab only the parts that we are going to use */ int16_t Channel[ACTUATORCOMMAND_CHANNEL_NUMELEM]; ActuatorCommandChannelGet(Channel); - MixerSettingsData mixerSettings; - MixerSettingsGet (&mixerSettings); - Mixer_t * mixers = (Mixer_t *)&mixerSettings.Mixer1Type; //pointer to array of mixers in UAVObjects + const Mixer_t * mixers = (Mixer_t *)&mixerSettings->Mixer1Type; //pointer to array of mixers in UAVObjects // Reset ActuatorCommand to safe values for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) @@ -521,11 +529,11 @@ static void setFailsafe() if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { - Channel[n] = ChannelMin[n]; + Channel[n] = actuatorSettings->ChannelMin[n]; } else if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_SERVO) { - Channel[n] = ChannelNeutral[n]; + Channel[n] = actuatorSettings->ChannelNeutral[n]; } else { @@ -541,54 +549,22 @@ static void setFailsafe() // Update servo outputs for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { - set_channel(n, Channel[n]); + set_channel(n, Channel[n], actuatorSettings); } // Update output object's parts that we changed ActuatorCommandChannelSet(Channel); } - -/** - * @brief Update the servo update rate - */ -static void actuator_update_rate(UAVObjEvent * ev) -{ - uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; - // ActuatoSettings are not changed - if ( ev->obj != ActuatorSettingsHandle() ) - return; - - ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq); - // check if the any rate setting is changed - if (lastChannelUpdateFreq[0]!=0 && memcmp(&lastChannelUpdateFreq[0], &ChannelUpdateFreq[0], sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM) ==0) - return; - // signal to the actuator task that ChannelUpdateFreq are changed - updateRateChanged = 1; -} -/** - * @brief Change the update rates according to the ActuatorSettingsChannelUpdateFreq. - */ -static void change_update_rate() -{ - uint16_t ChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; - // save the new rates - ActuatorSettingsChannelUpdateFreqGet(ChannelUpdateFreq); - memcpy(lastChannelUpdateFreq, ChannelUpdateFreq, sizeof(int16_t) * ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); - PIOS_Servo_SetHz(&ChannelUpdateFreq[0], ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); -} - #if defined(ARCH_POSIX) || defined(ARCH_WIN32) -static bool set_channel(uint8_t mixer_channel, uint16_t value) { +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings) +{ return true; } #else -static bool set_channel(uint8_t mixer_channel, uint16_t value) { - - ActuatorSettingsData settings; - ActuatorSettingsGet(&settings); - - switch(settings.ChannelType[mixer_channel]) { +static bool set_channel(uint8_t mixer_channel, uint16_t value, const ActuatorSettingsData * actuatorSettings) +{ + switch(actuatorSettings->ChannelType[mixer_channel]) { case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: { // This is for buzzers that take a PWM input @@ -631,18 +607,18 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { lastSysTime = thisSysTime; } } - PIOS_Servo_Set( settings.ChannelAddr[mixer_channel], - buzzOn?settings.ChannelMax[mixer_channel]:settings.ChannelMin[mixer_channel]); + PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], + buzzOn?actuatorSettings->ChannelMax[mixer_channel]:actuatorSettings->ChannelMin[mixer_channel]); return true; } case ACTUATORSETTINGS_CHANNELTYPE_PWM: - PIOS_Servo_Set(settings.ChannelAddr[mixer_channel], value); + PIOS_Servo_Set(actuatorSettings->ChannelAddr[mixer_channel], value); return true; #if defined(PIOS_INCLUDE_I2C_ESC) case ACTUATORSETTINGS_CHANNELTYPE_MK: - return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value); + return PIOS_SetMKSpeed(actuatorSettings->ChannelAddr[mixer_channel],value); case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4: - return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value); + return PIOS_SetAstec4Speed(actuatorSettings->ChannelAddr[mixer_channel],value); break; #endif default: @@ -654,6 +630,35 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { } #endif +/** + * @brief Update the servo update rate + */ +static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update) +{ + static uint16_t prevChannelUpdateFreq[ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM]; + + // check if the any rate setting is changed + if (force_update || + memcmp (prevChannelUpdateFreq, + actuatorSettings->ChannelUpdateFreq, + sizeof(prevChannelUpdateFreq)) != 0) { + /* Something has changed, apply the settings to HW */ + memcpy (prevChannelUpdateFreq, + actuatorSettings->ChannelUpdateFreq, + sizeof(prevChannelUpdateFreq)); + PIOS_Servo_SetHz(actuatorSettings->ChannelUpdateFreq, ACTUATORSETTINGS_CHANNELUPDATEFREQ_NUMELEM); + } +} + +static void ActuatorSettingsUpdatedCb(UAVObjEvent * ev) +{ + actuator_settings_updated = true; +} + +static void MixerSettingsUpdatedCb(UAVObjEvent * ev) +{ + mixer_settings_updated = true; +} /** * @} diff --git a/flight/PiOS.posix/inc/pios_servo.h b/flight/PiOS.posix/inc/pios_servo.h index 7cbf37a7d..952baa5a0 100644 --- a/flight/PiOS.posix/inc/pios_servo.h +++ b/flight/PiOS.posix/inc/pios_servo.h @@ -32,7 +32,7 @@ /* Public Functions */ extern void PIOS_Servo_Init(void); -extern void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t num_banks); +extern void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t num_banks); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); #endif /* PIOS_SERVO_H */ diff --git a/flight/PiOS.posix/posix/pios_servo.c b/flight/PiOS.posix/posix/pios_servo.c index 93b86a1ed..d0cf530d3 100644 --- a/flight/PiOS.posix/posix/pios_servo.c +++ b/flight/PiOS.posix/posix/pios_servo.c @@ -50,7 +50,7 @@ void PIOS_Servo_Init(void) * \param[in] onetofour Rate for outputs 1 to 4 (Hz) * \param[in] fivetoeight Rate for outputs 5 to 8 (Hz) */ -void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks) +void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks) { } diff --git a/flight/PiOS.win32/win32/pios_servo.c b/flight/PiOS.win32/win32/pios_servo.c index 93b86a1ed..d0cf530d3 100644 --- a/flight/PiOS.win32/win32/pios_servo.c +++ b/flight/PiOS.win32/win32/pios_servo.c @@ -50,7 +50,7 @@ void PIOS_Servo_Init(void) * \param[in] onetofour Rate for outputs 1 to 4 (Hz) * \param[in] fivetoeight Rate for outputs 5 to 8 (Hz) */ -void PIOS_Servo_SetHz(uint16_t * banks, uint8_t num_banks) +void PIOS_Servo_SetHz(const uint16_t * banks, uint8_t num_banks) { } diff --git a/flight/PiOS/STM32F10x/pios_servo.c b/flight/PiOS/STM32F10x/pios_servo.c index cb7d98292..46be375c2 100644 --- a/flight/PiOS/STM32F10x/pios_servo.c +++ b/flight/PiOS/STM32F10x/pios_servo.c @@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) * \param[in] array of rates in Hz * \param[in] maximum number of banks */ -void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) +void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks) { if (!servo_cfg) { return; diff --git a/flight/PiOS/STM32F4xx/pios_servo.c b/flight/PiOS/STM32F4xx/pios_servo.c index cfcf5c1e5..05188d563 100644 --- a/flight/PiOS/STM32F4xx/pios_servo.c +++ b/flight/PiOS/STM32F4xx/pios_servo.c @@ -87,7 +87,7 @@ int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) * \param[in] array of rates in Hz * \param[in] maximum number of banks */ -void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) +void PIOS_Servo_SetHz(const uint16_t * speeds, uint8_t banks) { if (!servo_cfg) { return; diff --git a/flight/PiOS/inc/pios_servo.h b/flight/PiOS/inc/pios_servo.h index 043d656df..1a33149ea 100644 --- a/flight/PiOS/inc/pios_servo.h +++ b/flight/PiOS/inc/pios_servo.h @@ -31,7 +31,7 @@ #define PIOS_SERVO_H /* Public Functions */ -extern void PIOS_Servo_SetHz(uint16_t * update_rates, uint8_t channels); +extern void PIOS_Servo_SetHz(const uint16_t * update_rates, uint8_t banks); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); #endif /* PIOS_SERVO_H */ From 62041f40ad6f746a38f5e913baf074c857133679 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sun, 12 Aug 2012 23:36:27 +0200 Subject: [PATCH 070/116] Changed variable from static to class static. --- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 6 +++--- .../src/libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index baaf8b24a..9ef52384b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -28,10 +28,11 @@ #include "uavitem.h" #include -static double groundspeed_mps_filt; - namespace mapcontrol { + + double UAVItem::groundspeed_mps_filt = 0; + UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) ,autosetdistance(100),altitude(0),showUAVInfo(false) { @@ -60,7 +61,6 @@ namespace mapcontrol Q_UNUSED(option); Q_UNUSED(widget); - //Draw plane painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 67ef23d65..8e59e268c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -248,7 +248,7 @@ namespace mapcontrol double Distance3D(internals::PointLatLng const& coord, int const& altitude); double autosetdistance; bool showUAVInfo; - // QRectF rect; + static double groundspeed_mps_filt; public slots: From a0977b405b31499acb4f18fb0e3092fd18c60b1c Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 13 Aug 2012 10:13:35 +0300 Subject: [PATCH 071/116] CameraStab UI: use ConfigTaskWidget API with objrelation dynamic property This supports most of widgets which are directly related to UAVObjects. --- .../src/plugins/config/camerastabilization.ui | 223 +++++++++++++++++- .../configcamerastabilizationwidget.cpp | 132 +---------- .../config/configcamerastabilizationwidget.h | 5 +- 3 files changed, 226 insertions(+), 134 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index e535faa50..dd06b8379 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -27,8 +27,8 @@ 0 0 - 696 - 635 + 702 + 660 @@ -107,6 +107,16 @@ have to define channel output range using Output configuration tab. 20 + + + objname:CameraStabSettings + fieldname:OutputRange + element:Yaw + haslimits:no + scale:1 + buttongroup:1 + + @@ -126,6 +136,16 @@ have to define channel output range using Output configuration tab. 20 + + + objname:CameraStabSettings + fieldname:OutputRange + element:Pitch + haslimits:no + scale:1 + buttongroup:1 + + @@ -145,6 +165,16 @@ have to define channel output range using Output configuration tab. 20 + + + objname:CameraStabSettings + fieldname:OutputRange + element:Roll + haslimits:no + scale:1 + buttongroup:1 + + @@ -339,6 +369,14 @@ margin:1px; Don't forget to map this channel using Input configuration tab. + + + objname:CameraStabSettings + fieldname:Input + element:Yaw + buttongroup:1 + + None @@ -356,6 +394,14 @@ Don't forget to map this channel using Input configuration tab. Don't forget to map this channel using Input configuration tab. + + + objname:CameraStabSettings + fieldname:Input + element:Pitch + buttongroup:1 + + None @@ -373,6 +419,14 @@ Don't forget to map this channel using Input configuration tab. Don't forget to map this channel using Input configuration tab. + + + objname:CameraStabSettings + fieldname:Input + element:Roll + buttongroup:1 + + None @@ -398,6 +452,14 @@ Don't forget to map this channel using Input configuration tab. Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + objname:CameraStabSettings + fieldname:StabilizationMode + element:Yaw + buttongroup:1 + + Attitude @@ -419,6 +481,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 20 + + + objname:CameraStabSettings + fieldname:InputRange + element:Yaw + haslimits:no + scale:1 + buttongroup:1 + + @@ -435,6 +507,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 50 + + + objname:CameraStabSettings + fieldname:InputRate + element:Yaw + haslimits:no + scale:1 + buttongroup:1 + + @@ -453,6 +535,16 @@ This option smoothes the stick input. Zero value disables LPF. 150 + + + objname:CameraStabSettings + fieldname:ResponseTime + element:Yaw + haslimits:no + scale:1 + buttongroup:1 + + @@ -466,6 +558,14 @@ This option smoothes the stick input. Zero value disables LPF. Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + objname:CameraStabSettings + fieldname:StabilizationMode + element:Pitch + buttongroup:1 + + Attitude @@ -487,6 +587,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 20 + + + objname:CameraStabSettings + fieldname:InputRange + element:Pitch + haslimits:no + scale:1 + buttongroup:1 + + @@ -503,6 +613,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 50 + + + objname:CameraStabSettings + fieldname:InputRate + element:Pitch + haslimits:no + scale:1 + buttongroup:1 + + @@ -521,6 +641,16 @@ This option smoothes the stick input. Zero value disables LPF. 150 + + + objname:CameraStabSettings + fieldname:ResponseTime + element:Pitch + haslimits:no + scale:1 + buttongroup:1 + + @@ -534,6 +664,14 @@ This option smoothes the stick input. Zero value disables LPF. Attitude: camera tracks level for the axis. Input controls the deflection. AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + objname:CameraStabSettings + fieldname:StabilizationMode + element:Roll + buttongroup:1 + + Attitude @@ -555,6 +693,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 20 + + + objname:CameraStabSettings + fieldname:InputRange + element:Roll + haslimits:no + scale:1 + buttongroup:1 + + @@ -571,6 +719,16 @@ AxisLock: camera remembers tracking attitude. Input controls the rate of deflect 50 + + + objname:CameraStabSettings + fieldname:InputRate + element:Roll + haslimits:no + scale:1 + buttongroup:1 + + @@ -589,6 +747,16 @@ This option smoothes the stick input. Zero value disables LPF. 150 + + + objname:CameraStabSettings + fieldname:ResponseTime + element:Roll + haslimits:no + scale:1 + buttongroup:1 + + @@ -657,6 +825,15 @@ value. 1.000000000000000 + + + objname:CameraStabSettings + fieldname:MaxAxisLockRate + haslimits:no + scale:1 + buttongroup:1 + + @@ -754,6 +931,32 @@ value. true + + + button:help + url:http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration + + + + + + + + Reloads current data from board into GCS. +Useful if you have accidentally changed some settings. + +Loaded settings are not applied automatically. You have to click the +Apply or Save button afterwards. + + + Reload Board Data + + + + button:reload + buttongroup:1 + + @@ -767,6 +970,12 @@ Apply or Save button afterwards. Reset To Defaults + + + button:default + buttongroup:1 + + @@ -777,6 +986,11 @@ Apply or Save button afterwards. Apply + + + button:apply + + @@ -790,6 +1004,11 @@ Apply or Save button afterwards. false + + + button:save + + diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 3e757de63..51b944d83 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -36,60 +36,26 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { - // TODO: this widget should use the addUAVObjectToWidgetRelation() m_camerastabilization = new Ui_CameraStabilizationWidget(); m_camerastabilization->setupUi(this); + // These comboboxes require special processing QComboBox *outputs[3] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, m_camerastabilization->yawChannel, }; - QComboBox *inputs[3] = { - m_camerastabilization->rollInputChannel, - m_camerastabilization->pitchInputChannel, - m_camerastabilization->yawInputChannel, - }; - - QComboBox *stabilizationMode[3] = { - m_camerastabilization->rollStabilizationMode, - m_camerastabilization->pitchStabilizationMode, - m_camerastabilization->yawStabilizationMode, - }; - - CameraStabSettings *cameraStab = CameraStabSettings::GetInstance(getObjectManager()); - CameraStabSettings::DataFields cameraStabData = cameraStab->getData(); - for (int i = 0; i < 3; i++) { outputs[i]->clear(); outputs[i]->addItem("None"); for (quint32 j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++) outputs[i]->addItem(QString("Channel %1").arg(j+1)); - - UAVObjectField *field; - - field = cameraStab->getField("Input"); - Q_ASSERT(field); - inputs[i]->clear(); - inputs[i]->addItems(field->getOptions()); - inputs[i]->setCurrentIndex(cameraStabData.Input[i]); - - field = cameraStab->getField("StabilizationMode"); - Q_ASSERT(field); - stabilizationMode[i]->clear(); - stabilizationMode[i]->addItems(field->getOptions()); - stabilizationMode[i]->setCurrentIndex(cameraStabData.StabilizationMode[i]); } - connectUpdates(); - - // Connect buttons - connect(m_camerastabilization->camerastabilizationResetToDefaults, SIGNAL(clicked()), this, SLOT(resetToDefaults())); - connect(m_camerastabilization->camerastabilizationSaveRAM, SIGNAL(clicked()), this, SLOT(applySettings())); - connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings())); - connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - + autoLoadWidgets(); + populateWidgets(); + refreshWidgetsValues(); disableMouseWheelEvents(); } @@ -102,7 +68,6 @@ void ConfigCameraStabilizationWidget::connectUpdates() { // Now connect the widget to the StabilizationSettings object connect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); - connect(CameraStabSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); // TODO: This will need to support both CC and OP later connect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); } @@ -111,7 +76,6 @@ void ConfigCameraStabilizationWidget::disconnectUpdates() { // Now connect the widget to the StabilizationSettings object disconnect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); - disconnect(CameraStabSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); // TODO: This will need to support both CC and OP later disconnect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); } @@ -182,36 +146,6 @@ void ConfigCameraStabilizationWidget::applySettings() } } - // Update the settings - CameraStabSettings *cameraStab = CameraStabSettings::GetInstance(getObjectManager()); - CameraStabSettings::DataFields cameraStabData = cameraStab->getData(); - - cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL] = m_camerastabilization->rollOutputRange->value(); - cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH] = m_camerastabilization->pitchOutputRange->value(); - cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW] = m_camerastabilization->yawOutputRange->value(); - - cameraStabData.Input[CameraStabSettings::INPUT_ROLL] = m_camerastabilization->rollInputChannel->currentIndex(); - cameraStabData.Input[CameraStabSettings::INPUT_PITCH] = m_camerastabilization->pitchInputChannel->currentIndex(); - cameraStabData.Input[CameraStabSettings::INPUT_YAW] = m_camerastabilization->yawInputChannel->currentIndex(); - - cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_ROLL] = m_camerastabilization->rollStabilizationMode->currentIndex(); - cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_PITCH] = m_camerastabilization->pitchStabilizationMode->currentIndex(); - cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_YAW] = m_camerastabilization->yawStabilizationMode->currentIndex(); - - cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_ROLL] = m_camerastabilization->rollInputRange->value(); - cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_PITCH] = m_camerastabilization->pitchInputRange->value(); - cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_YAW] = m_camerastabilization->yawInputRange->value(); - - cameraStabData.InputRate[CameraStabSettings::INPUTRATE_ROLL] = m_camerastabilization->rollInputRate->value(); - cameraStabData.InputRate[CameraStabSettings::INPUTRATE_PITCH] = m_camerastabilization->pitchInputRate->value(); - cameraStabData.InputRate[CameraStabSettings::INPUTRATE_YAW] = m_camerastabilization->yawInputRate->value(); - - cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_ROLL] = m_camerastabilization->rollResponseTime->value(); - cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_PITCH] = m_camerastabilization->pitchResponseTime->value(); - cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_YAW] = m_camerastabilization->yawResponseTime->value(); - - cameraStabData.MaxAxisLockRate = m_camerastabilization->MaxAxisLockRate->value(); - // Because multiple objects are updated, and all of them trigger the callback // they must be done together (if update one then load settings from second // the first update would wipe the UI controls). However to be extra cautious @@ -219,7 +153,6 @@ void ConfigCameraStabilizationWidget::applySettings() disconnectUpdates(); hwSettings->setData(hwSettingsData); mixerSettings->setData(mixerSettingsData); - cameraStab->setData(cameraStabData); connectUpdates(); } @@ -237,40 +170,6 @@ void ConfigCameraStabilizationWidget::saveSettings() saveObjectToSD(obj); } -/** - * Refresh UI with new settings of CameraStabSettings object - * (either from active configuration or just loaded defaults - * to be applied or saved) - */ -void ConfigCameraStabilizationWidget::refreshUIValues(CameraStabSettings::DataFields &cameraStabData) -{ - m_camerastabilization->rollOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL]); - m_camerastabilization->pitchOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH]); - m_camerastabilization->yawOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW]); - - m_camerastabilization->rollInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_ROLL]); - m_camerastabilization->pitchInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_PITCH]); - m_camerastabilization->yawInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_YAW]); - - m_camerastabilization->rollStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_ROLL]); - m_camerastabilization->pitchStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_PITCH]); - m_camerastabilization->yawStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_YAW]); - - m_camerastabilization->rollInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_ROLL]); - m_camerastabilization->pitchInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_PITCH]); - m_camerastabilization->yawInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_YAW]); - - m_camerastabilization->rollInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_ROLL]); - m_camerastabilization->pitchInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_PITCH]); - m_camerastabilization->yawInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_YAW]); - - m_camerastabilization->rollResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_ROLL]); - m_camerastabilization->pitchResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_PITCH]); - m_camerastabilization->yawResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_YAW]); - - m_camerastabilization->MaxAxisLockRate->setValue(cameraStabData.MaxAxisLockRate); -} - void ConfigCameraStabilizationWidget::refreshValues() { HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); @@ -279,10 +178,6 @@ void ConfigCameraStabilizationWidget::refreshValues() hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); - CameraStabSettings *cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager()); - CameraStabSettings::DataFields cameraStabData = cameraStabSettings->getData(); - refreshUIValues(cameraStabData); - MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); const int NUM_MIXERS = 10; @@ -319,25 +214,6 @@ void ConfigCameraStabilizationWidget::refreshValues() } } -void ConfigCameraStabilizationWidget::resetToDefaults() -{ - CameraStabSettings cameraStabDefaults; - CameraStabSettings::DataFields defaults = cameraStabDefaults.getData(); - refreshUIValues(defaults); -} - -void ConfigCameraStabilizationWidget::openHelp() -{ - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration", QUrl::StrictMode) ); -} - -void ConfigCameraStabilizationWidget::enableControls(bool enable) -{ - m_camerastabilization->camerastabilizationResetToDefaults->setEnabled(enable); - m_camerastabilization->camerastabilizationSaveSD->setEnabled(enable); - m_camerastabilization->camerastabilizationSaveRAM->setEnabled(enable); -} - /** @} @} diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 743435adb..7c86ae021 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -41,14 +41,11 @@ class ConfigCameraStabilizationWidget: public ConfigTaskWidget public: ConfigCameraStabilizationWidget(QWidget *parent = 0); ~ConfigCameraStabilizationWidget(); + private: Ui_CameraStabilizationWidget *m_camerastabilization; - virtual void enableControls(bool enable); - void refreshUIValues(CameraStabSettings::DataFields &cameraStabData); private slots: - void openHelp(); - void resetToDefaults(); void applySettings(); void saveSettings(); void refreshValues(); From c8e90a537e2056b914541ac1c73c01970e96d7a0 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 14 Aug 2012 17:15:53 +0300 Subject: [PATCH 072/116] CameraStab UI: use ConfigTaskWidget API to take care of other widgets --- .../src/plugins/config/camerastabilization.ui | 44 ++-- .../configcamerastabilizationwidget.cpp | 224 +++++++++--------- .../config/configcamerastabilizationwidget.h | 11 +- 3 files changed, 132 insertions(+), 147 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index dd06b8379..a394820e7 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -939,30 +939,10 @@ value. - - - - Reloads current data from board into GCS. -Useful if you have accidentally changed some settings. - -Loaded settings are not applied automatically. You have to click the -Apply or Save button afterwards. - - - Reload Board Data - - - - button:reload - buttongroup:1 - - - - - Load default CameraStabilization settings except output channels + Load default CameraStabilization settings except output channels into GCS. Loaded settings are not applied automatically. You have to click the Apply or Save button afterwards. @@ -978,6 +958,27 @@ Apply or Save button afterwards. + + + + Reloads saved CameraStabilization settings except output channels +from board into GCS. Useful if you have accidentally changed some +settings. + +Loaded settings are not applied automatically. You have to click the +Apply or Save button afterwards. + + + Reload Board Data + + + + button:reload + buttongroup:1 + + + + @@ -1042,7 +1043,6 @@ Apply or Save button afterwards. yawResponseTime MaxAxisLockRate camerastabilizationHelp - camerastabilizationResetToDefaults camerastabilizationSaveRAM camerastabilizationSaveSD scrollArea diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 51b944d83..0a72be67d 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -30,32 +30,41 @@ #include "mixersettings.h" #include "actuatorcommand.h" -#include -#include -#include - ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { m_camerastabilization = new Ui_CameraStabilizationWidget(); m_camerastabilization->setupUi(this); - // These comboboxes require special processing - QComboBox *outputs[3] = { + // These widgets don't have direct relation to UAVObjects + // and need special processing + QComboBox *outputs[] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, m_camerastabilization->yawChannel, }; + const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); - for (int i = 0; i < 3; i++) { + // Populate widgets with channel numbers + for (int i = 0; i < NUM_OUTPUTS; i++) { outputs[i]->clear(); outputs[i]->addItem("None"); for (quint32 j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++) outputs[i]->addItem(QString("Channel %1").arg(j+1)); } + // Load UAVObjects to widget relations from UI file + // using objrelation dynamic property autoLoadWidgets(); - populateWidgets(); - refreshWidgetsValues(); + + // Add some widgets and UAVObjects to track widget dirty state + // and monitor UAVObject changes in addition to autoloaded ones + addWidget(m_camerastabilization->enableCameraStabilization); + addWidget(m_camerastabilization->rollChannel); + addWidget(m_camerastabilization->pitchChannel); + addWidget(m_camerastabilization->yawChannel); + addUAVObject("HwSettings"); + addUAVObject("MixerSettings"); + disableMouseWheelEvents(); } @@ -64,50 +73,32 @@ ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() // Do nothing } -void ConfigCameraStabilizationWidget::connectUpdates() +/* + * This overridden function refreshes widgets which have no direct relation + * to any of UAVObjects. It saves their dirty state first because update comes + * from UAVObjects, and then restores it. Aftewards it calls base class + * function to take care of other widgets which were dynamically added. + */ +void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) { - // Now connect the widget to the StabilizationSettings object - connect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); - // TODO: This will need to support both CC and OP later - connect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); -} + bool dirty = isDirty(); -void ConfigCameraStabilizationWidget::disconnectUpdates() -{ - // Now connect the widget to the StabilizationSettings object - disconnect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); - // TODO: This will need to support both CC and OP later - disconnect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); -} - -/** - * @brief Populate the gui settings into the appropriate - * UAV structures - */ -void ConfigCameraStabilizationWidget::applySettings() -{ - // Enable or disable the settings + // Set module enable checkbox from OptionalModules UAVObject item. + // It needs special processing because ConfigTaskWidget uses TRUE/FALSE + // for QCheckBox, but OptionalModules uses Enabled/Disabled enum values. HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); - hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] = - m_camerastabilization->enableCameraStabilization->isChecked() ? - HwSettings::OPTIONALMODULES_ENABLED : - HwSettings::OPTIONALMODULES_DISABLED; - // Update the mixer settings + m_camerastabilization->enableCameraStabilization->setChecked( + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); + + // Load mixer outputs which are mapped to camera controls MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); - const int NUM_MIXERS = 10; - - QComboBox *outputs[3] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel, - }; // TODO: Need to reformat object so types are an // array themselves. This gets really awkward - quint8 * mixerTypes[NUM_MIXERS] = { + quint8 *mixerTypes[] = { &mixerSettingsData.Mixer1Type, &mixerSettingsData.Mixer2Type, &mixerSettingsData.Mixer3Type, @@ -119,18 +110,83 @@ void ConfigCameraStabilizationWidget::applySettings() &mixerSettingsData.Mixer9Type, &mixerSettingsData.Mixer10Type, }; + const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); + + QComboBox *outputs[] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel + }; + const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); + + for (int i = 0; i < NUM_OUTPUTS; i++) { + // Default to none if not found. + // Then search for any mixer channels set to this + outputs[i]->setCurrentIndex(0); + for (int j = 0; j < NUM_MIXERS; j++) + if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i) && + outputs[i]->currentIndex() != (j + 1)) + outputs[i]->setCurrentIndex(j + 1); + } + + setDirty(dirty); + + ConfigTaskWidget::refreshWidgetsValues(obj); +} + +/* + * This overridden function updates UAVObjects which have no direct relation + * to any of widgets. Aftewards it calls base class function to take care of + * other object to widget relations which were dynamically added. + */ +void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() +{ + // Save state of the module enable checkbox first + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings::DataFields hwSettingsData = hwSettings->getData(); + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] = + m_camerastabilization->enableCameraStabilization->isChecked() ? + HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; + hwSettings->setData(hwSettingsData); + + // Update mixer channels which were mapped to camera outputs in case they are + // not used for other function yet + MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); + MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); + + // TODO: Need to reformat object so types are an + // array themselves. This gets really awkward + quint8 *mixerTypes[] = { + &mixerSettingsData.Mixer1Type, + &mixerSettingsData.Mixer2Type, + &mixerSettingsData.Mixer3Type, + &mixerSettingsData.Mixer4Type, + &mixerSettingsData.Mixer5Type, + &mixerSettingsData.Mixer6Type, + &mixerSettingsData.Mixer7Type, + &mixerSettingsData.Mixer8Type, + &mixerSettingsData.Mixer9Type, + &mixerSettingsData.Mixer10Type, + }; + const int NUM_MIXERS = sizeof(mixerTypes) / sizeof(mixerTypes[0]); + + QComboBox *outputs[] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel + }; + const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); m_camerastabilization->message->setText(""); - for (int i = 0; i < 3; i++) - { + for (int i = 0; i < NUM_OUTPUTS; i++) { // Channel 1 is second entry, so becomes zero int mixerNum = outputs[i]->currentIndex() - 1; - if ( mixerNum >= 0 && // Short circuit in case of none - *mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED && - (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { - // If the mixer channel already to something that isn't what we are - // about to set it to reset to none + if ((mixerNum >= 0) && // Short circuit in case of none + (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED) && + (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { + // If the mixer channel already mapped to something, it should not be + // used for camera output, we reset it to none outputs[i]->setCurrentIndex(0); m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); } else { @@ -141,77 +197,13 @@ void ConfigCameraStabilizationWidget::applySettings() // If this channel is assigned to one of the outputs that is not disabled // set it - if(mixerNum >= 0 && mixerNum < NUM_MIXERS) + if ((mixerNum >= 0) && (mixerNum < NUM_MIXERS)) *mixerTypes[mixerNum] = MixerSettings::MIXER1TYPE_CAMERAROLL + i; } } - - // Because multiple objects are updated, and all of them trigger the callback - // they must be done together (if update one then load settings from second - // the first update would wipe the UI controls). However to be extra cautious - // I'm also disabling updates during the setting to the UAVObjects - disconnectUpdates(); - hwSettings->setData(hwSettingsData); mixerSettings->setData(mixerSettingsData); - connectUpdates(); -} -/** - * Push settings into UAV objects then save them - */ -void ConfigCameraStabilizationWidget::saveSettings() -{ - applySettings(); - UAVObject *obj = HwSettings::GetInstance(getObjectManager()); - saveObjectToSD(obj); - obj = MixerSettings::GetInstance(getObjectManager()); - saveObjectToSD(obj); - obj = CameraStabSettings::GetInstance(getObjectManager()); - saveObjectToSD(obj); -} - -void ConfigCameraStabilizationWidget::refreshValues() -{ - HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); - HwSettings::DataFields hwSettingsData = hwSettings->getData(); - m_camerastabilization->enableCameraStabilization->setChecked( - hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == - HwSettings::OPTIONALMODULES_ENABLED); - - MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); - MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); - const int NUM_MIXERS = 10; - QComboBox *outputs[3] = { - m_camerastabilization->rollChannel, - m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel - }; - - // TODO: Need to reformat object so types are an - // array themselves. This gets really awkward - quint8 * mixerTypes[NUM_MIXERS] = { - &mixerSettingsData.Mixer1Type, - &mixerSettingsData.Mixer2Type, - &mixerSettingsData.Mixer3Type, - &mixerSettingsData.Mixer4Type, - &mixerSettingsData.Mixer5Type, - &mixerSettingsData.Mixer6Type, - &mixerSettingsData.Mixer7Type, - &mixerSettingsData.Mixer8Type, - &mixerSettingsData.Mixer9Type, - &mixerSettingsData.Mixer10Type, - }; - - for (int i = 0; i < 3; i++) - { - // Default to none if not found. Then search for any mixer channels set to - // this - outputs[i]->setCurrentIndex(0); - for (int j = 0; j < NUM_MIXERS; j++) - if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i) && - outputs[i]->currentIndex() != (j + 1)) - outputs[i]->setCurrentIndex(j + 1); - } + ConfigTaskWidget::updateObjectsFromWidgets(); } /** diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 7c86ae021..1b4230254 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -44,15 +44,8 @@ public: private: Ui_CameraStabilizationWidget *m_camerastabilization; - -private slots: - void applySettings(); - void saveSettings(); - void refreshValues(); - -protected: - void connectUpdates(); - void disconnectUpdates(); + void refreshWidgetsValues(UAVObject *obj); + void updateObjectsFromWidgets(); }; #endif // CONFIGCAMERASTABILIZATIONWIDGET_H From 64e5ff8e6dd991c2204483cec628e560cfaaf354 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 14 Aug 2012 17:52:44 +0300 Subject: [PATCH 073/116] CameraStab UI: rescan widget if changed during UAVObject update --- .../configcamerastabilizationwidget.cpp | 49 +++++++++++-------- 1 file changed, 29 insertions(+), 20 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 0a72be67d..95bcbbb28 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -178,29 +178,38 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); m_camerastabilization->message->setText(""); - for (int i = 0; i < NUM_OUTPUTS; i++) { - // Channel 1 is second entry, so becomes zero - int mixerNum = outputs[i]->currentIndex() - 1; + bool widgetUpdated; + do { + widgetUpdated = false; - if ((mixerNum >= 0) && // Short circuit in case of none - (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED) && - (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { - // If the mixer channel already mapped to something, it should not be - // used for camera output, we reset it to none - outputs[i]->setCurrentIndex(0); - m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); - } else { - // Make sure no other channels have this output set - for (int j = 0; j < NUM_MIXERS; j++) - if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i)) - *mixerTypes[j] = MixerSettings::MIXER1TYPE_DISABLED; + for (int i = 0; i < NUM_OUTPUTS; i++) { + // Channel 1 is second entry, so becomes zero + int mixerNum = outputs[i]->currentIndex() - 1; - // If this channel is assigned to one of the outputs that is not disabled - // set it - if ((mixerNum >= 0) && (mixerNum < NUM_MIXERS)) - *mixerTypes[mixerNum] = MixerSettings::MIXER1TYPE_CAMERAROLL + i; + if ((mixerNum >= 0) && // Short circuit in case of none + (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED) && + (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { + // If the mixer channel already mapped to something, it should not be + // used for camera output, we reset it to none + outputs[i]->setCurrentIndex(0); + m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); + + // Loop again or we may have inconsistent widget and UAVObject + widgetUpdated = true; + } else { + // Make sure no other channels have this output set + for (int j = 0; j < NUM_MIXERS; j++) + if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i)) + *mixerTypes[j] = MixerSettings::MIXER1TYPE_DISABLED; + + // If this channel is assigned to one of the outputs that is not disabled + // set it + if ((mixerNum >= 0) && (mixerNum < NUM_MIXERS)) + *mixerTypes[mixerNum] = MixerSettings::MIXER1TYPE_CAMERAROLL + i; + } } - } + } while(widgetUpdated); + mixerSettings->setData(mixerSettingsData); ConfigTaskWidget::updateObjectsFromWidgets(); From 0f8974178a96337a3f888fb83a14225be9aa568a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 14 Aug 2012 18:12:07 +0100 Subject: [PATCH 074/116] GCS-Fixes crash if autoLoadWidgets is called after addUAVObject --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7fb8d70c7..7bfbfb0c3 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -698,10 +698,12 @@ void ConfigTaskWidget::autoLoadWidgets() forceShadowUpdates(); foreach(objectToWidget * ow,objOfInterest) { - qDebug()<<"Master:"<widget->objectName(); + if(ow->widget) + qDebug()<<"Master:"<widget->objectName(); foreach(shadow * sh,ow->shadowsList) { - qDebug()<<"Child"<widget->objectName(); + if(sh->widget) + qDebug()<<"Child"<widget->objectName(); } } } From 2ddb0e63d2d37d4fbd662504f865f4f5aa85fbf5 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 14 Aug 2012 23:02:08 +0100 Subject: [PATCH 075/116] GCS-Couple of bug fixes and created a new defaultRequested signal --- .../plugins/config/configcamerastabilizationwidget.cpp | 5 +++++ .../src/plugins/config/configcamerastabilizationwidget.h | 2 ++ .../plugins/uavobjectwidgetutils/configtaskwidget.cpp | 9 +++------ .../src/plugins/uavobjectwidgetutils/configtaskwidget.h | 2 +- .../src/plugins/uavobjectwidgetutils/smartsavebutton.cpp | 1 + 5 files changed, 12 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 95bcbbb28..95c58573b 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -66,6 +66,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent addUAVObject("MixerSettings"); disableMouseWheelEvents(); + connect(this,SIGNAL(defaultRequested(int)),this,SLOT(defaultRequestedSlot(int))); } ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() @@ -214,6 +215,10 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() ConfigTaskWidget::updateObjectsFromWidgets(); } +void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) +{ + +} /** @} diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 1b4230254..6c1a8d888 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -46,6 +46,8 @@ private: Ui_CameraStabilizationWidget *m_camerastabilization; void refreshWidgetsValues(UAVObject *obj); void updateObjectsFromWidgets(); +private slots: + void defaultRequestedSlot(int group); }; #endif // CONFIGCAMERASTABILIZATIONWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7bfbfb0c3..bd95532dd 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,7 +32,7 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),allowWidgetUpdates(true) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); @@ -176,10 +176,6 @@ ConfigTaskWidget::~ConfigTaskWidget() if(oTw) delete oTw; } - if(timeOut) - { - delete timeOut; - } } void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) @@ -772,6 +768,7 @@ void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup) void ConfigTaskWidget::defaultButtonClicked() { int group=sender()->property("group").toInt(); + emit defaultRequested(group); QList * list=defaultReloadGroups.value(group); foreach(objectToWidget * oTw,*list) { @@ -791,7 +788,7 @@ void ConfigTaskWidget::reloadButtonClicked() if(!list) return; ObjectPersistence* objper = dynamic_cast( getObjectManager()->getObject(ObjectPersistence::NAME) ); - timeOut=new QTimer(this); + QTimer * timeOut=new QTimer(this); QEventLoop * eventLoop=new QEventLoop(this); connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 3cac0abc0..ef2d9cd20 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -139,6 +139,7 @@ signals: void autoPilotConnected(); //fired when the autopilot disconnects void autoPilotDisconnected(); + void defaultRequested(int group); private slots: void objectUpdated(UAVObject*); void defaultButtonClicked(); @@ -165,7 +166,6 @@ private: void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; - QTimer * timeOut; protected slots: virtual void disableObjUpdates(); virtual void enableObjUpdates(); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp index 9b0268a4e..28fe3c997 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/smartsavebutton.cpp @@ -151,6 +151,7 @@ void smartSaveButton::setObjects(QList list) void smartSaveButton::addObject(UAVDataObject * obj) { + Q_ASSERT(obj); if(!objects.contains(obj)) objects.append(obj); } From ae962f507bb0736e3889d43ce5b784645b027e96 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Tue, 14 Aug 2012 23:55:53 +0100 Subject: [PATCH 076/116] GCS-Couple of bug fixes and created a new defaultRequested signal --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 4 +++- .../src/plugins/uavobjectwidgetutils/configtaskwidget.h | 1 + 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index bd95532dd..cdff00e53 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -783,12 +783,14 @@ void ConfigTaskWidget::defaultButtonClicked() */ void ConfigTaskWidget::reloadButtonClicked() { + if(timeOut) + return; int group=sender()->property("group").toInt(); QList * list=defaultReloadGroups.value(group,NULL); if(!list) return; ObjectPersistence* objper = dynamic_cast( getObjectManager()->getObject(ObjectPersistence::NAME) ); - QTimer * timeOut=new QTimer(this); + timeOut=new QTimer(this); QEventLoop * eventLoop=new QEventLoop(this); connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit())); connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit())); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index ef2d9cd20..25281a942 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -166,6 +166,7 @@ private: void disconnectWidgetUpdatesToSlot(QWidget *widget, const char *function); void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale); QString outOfLimitsStyle; + QTimer * timeOut; protected slots: virtual void disableObjUpdates(); virtual void enableObjUpdates(); From d3c5fcfa7e10d1d9d64d5e2a6239200951c3daf7 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 15 Aug 2012 00:13:26 +0100 Subject: [PATCH 077/116] GCS-Handle reload operation config camera stab --- .../config/configcamerastabilizationwidget.cpp | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 95c58573b..74b89a653 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -217,7 +217,21 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() } void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) { + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings *hwSettingsDefault=(HwSettings*)hwSettings->dirtyClone(); + HwSettings::DataFields hwSettingsData = hwSettingsDefault->getData(); + m_camerastabilization->enableCameraStabilization->setChecked( + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); + QComboBox *outputs[] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel, + }; + const int NUM_OUTPUTS = sizeof(outputs) / sizeof(outputs[0]); + for (int i = 0; i < NUM_OUTPUTS; i++) { + outputs[i]->setCurrentIndex(0); + } } /** From fd9f1491bae442b3ace5a1c0108b29a3baad7ce5 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Wed, 15 Aug 2012 10:31:19 +0300 Subject: [PATCH 078/116] CameraStab UI: fix spacing and add comments according to OP coding style guidelines More info: http://wiki.openpilot.org/display/Doc/Coding+Style http://qt-project.org/wiki/Qt_Coding_Style --- .../config/configcamerastabilizationwidget.cpp | 12 +++++++++++- .../plugins/config/configcamerastabilizationwidget.h | 1 + 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 74b89a653..b28453d38 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -65,8 +65,10 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent addUAVObject("HwSettings"); addUAVObject("MixerSettings"); + // To set special widgets to defaults when requested + connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int))); + disableMouseWheelEvents(); - connect(this,SIGNAL(defaultRequested(int)),this,SLOT(defaultRequestedSlot(int))); } ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() @@ -215,13 +217,21 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() ConfigTaskWidget::updateObjectsFromWidgets(); } + +/* + * This slot function is called when "Default" button is clicked. + * All special widgets which belong to the group passed should be set here. + */ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) { + Q_UNUSED(group); + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings *hwSettingsDefault=(HwSettings*)hwSettings->dirtyClone(); HwSettings::DataFields hwSettingsData = hwSettingsDefault->getData(); m_camerastabilization->enableCameraStabilization->setChecked( hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); + QComboBox *outputs[] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index 6c1a8d888..871193e82 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -46,6 +46,7 @@ private: Ui_CameraStabilizationWidget *m_camerastabilization; void refreshWidgetsValues(UAVObject *obj); void updateObjectsFromWidgets(); + private slots: void defaultRequestedSlot(int group); }; From 93124bbfeeffa4f89b7b9f133335c61591402561 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 15 Aug 2012 12:37:00 +0100 Subject: [PATCH 079/116] GCS-Fixed reload operation, sorry Oleg --- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index cdff00e53..1e0246882 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,7 +32,7 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),allowWidgetUpdates(true) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); From 57d4aaaf170a298feecdd8d0654073526b69f7a8 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Wed, 15 Aug 2012 22:50:09 +0100 Subject: [PATCH 080/116] GCS-Handle reload for unbounded objects --- .../configcamerastabilizationwidget.cpp | 6 +++-- .../uavobjectwidgetutils/configtaskwidget.cpp | 27 ++++++++++++++----- .../uavobjectwidgetutils/configtaskwidget.h | 2 +- 3 files changed, 26 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index b28453d38..6defa9a6a 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -56,14 +56,16 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent // using objrelation dynamic property autoLoadWidgets(); + QList reloadGroups; + reloadGroups<<1; // Add some widgets and UAVObjects to track widget dirty state // and monitor UAVObject changes in addition to autoloaded ones addWidget(m_camerastabilization->enableCameraStabilization); addWidget(m_camerastabilization->rollChannel); addWidget(m_camerastabilization->pitchChannel); addWidget(m_camerastabilization->yawChannel); - addUAVObject("HwSettings"); - addUAVObject("MixerSettings"); + addUAVObject("HwSettings",&reloadGroups); + addUAVObject("MixerSettings",&reloadGroups); // To set special widgets to defaults when requested connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int))); diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 1e0246882..a947ffe6e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -57,9 +57,9 @@ void ConfigTaskWidget::addWidget(QWidget * widget) * Add an object to the management system * @param objectName name of the object to add to the management system */ -void ConfigTaskWidget::addUAVObject(QString objectName) +void ConfigTaskWidget::addUAVObject(QString objectName,QList * reloadGroups) { - addUAVObjectToWidgetRelation(objectName,"",NULL); + addUAVObjectToWidgetRelation(objectName,"",NULL,0,1,false,reloadGroups); } /** * Add an UAVObject field to widget relation to the management system @@ -148,7 +148,21 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel } if(widget==NULL) { - // do nothing + if(defaultReloadGroups && obj) + { + foreach(int i,*defaultReloadGroups) + { + if(this->defaultReloadGroups.contains(i)) + { + this->defaultReloadGroups.value(i)->append(ow); + } + else + { + this->defaultReloadGroups.insert(i,new QList()); + this->defaultReloadGroups.value(i)->append(ow); + } + } + } } else { @@ -537,7 +551,7 @@ bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *w { foreach(objectToWidget * oTw,objOfInterest) { - if(!oTw->object || !oTw->widget) + if(!oTw->object || !oTw->widget || !oTw->field) continue; if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index && oTw->object->getInstID()==instID) { @@ -772,7 +786,7 @@ void ConfigTaskWidget::defaultButtonClicked() QList * list=defaultReloadGroups.value(group); foreach(objectToWidget * oTw,*list) { - if(!oTw->object) + if(!oTw->object || !oTw->field) continue; UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone(); setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale,oTw->isLimited); @@ -810,7 +824,8 @@ void ConfigTaskWidget::reloadButtonClicked() if(timeOut->isActive()) { oTw->object->requestUpdate(); - setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited); + if(oTw->widget) + setWidgetFromField(oTw->widget,oTw->field,oTw->index,oTw->scale,oTw->isLimited); } timeOut->stop(); } diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 25281a942..f4f0b6b9c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -93,7 +93,7 @@ public: UAVObjectManager* getObjectManager(); static double listMean(QList list); - void addUAVObject(QString objectName); + void addUAVObject(QString objectName, QList *reloadGroups=NULL); void addWidget(QWidget * widget); void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); From 7e55b31ca17d490aead1f73ded4a70a38814e715 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Fri, 17 Aug 2012 09:46:35 +0200 Subject: [PATCH 081/116] Fixed bounding box size. Conflicts: ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 19 +++++++++++++------ .../libs/opmapcontrol/src/mapwidget/uavitem.h | 2 ++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 1 - 3 files changed, 15 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 9ef52384b..f96d0815d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -34,7 +34,7 @@ namespace mapcontrol double UAVItem::groundspeed_mps_filt = 0; UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100),altitude(0),showUAVInfo(false) + ,autosetdistance(100),altitude(0),showUAVInfo(false),showJustChanged(false) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,true); @@ -65,8 +65,10 @@ namespace mapcontrol painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); //Return if context menu switch for UAV info is off - if(!showUAVInfo) + if(!showUAVInfo){ + showJustChanged=false; return; + } QPen myPen; @@ -81,9 +83,6 @@ namespace mapcontrol myPen.setColor(myColor); painter->setPen(myPen); - //Set brush attributes -// painter->setBrush(myColor); - //Create line from (0,0), to (1,1). Later, we'll scale and rotate it QLineF line(0,0,1.0,1.0); @@ -232,11 +231,17 @@ namespace mapcontrol painter->setPen(myPen); painter->drawPath(path); + + //Last thing to do: set bound rectangle as function of largest object + boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+10; //Largest object is currently the biggest ring + a little bit of margin for the text } QRectF UAVItem::boundingRect()const { - return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); + if(showUAVInfo || showJustChanged) + return QRectF(-boundingRectSize,-boundingRectSize,2*boundingRectSize,2*boundingRectSize); + else + return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); } void UAVItem::SetNED(double NED[3]){ @@ -425,6 +430,8 @@ namespace mapcontrol void UAVItem::SetShowUAVInfo(bool const& value) { showUAVInfo=value; + showJustChanged=true; + update(); } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 8e59e268c..155f61581 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -249,6 +249,8 @@ namespace mapcontrol double autosetdistance; bool showUAVInfo; static double groundspeed_mps_filt; + float boundingRectSize; + bool showJustChanged; public slots: diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index bcc1de88b..155e0a741 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1555,7 +1555,6 @@ void OPMapGadgetWidget::onShowUAVInfo_toggled(bool show) return; m_map->UAV->SetShowUAVInfo(show); - update(); } void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) From e52d141e3e4f18b5223c638a3f0f4215e495ba99 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Fri, 17 Aug 2012 10:11:45 +0200 Subject: [PATCH 082/116] Improved bounding rect dimensioning. --- .../libs/opmapcontrol/src/mapwidget/uavitem.cpp | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index f96d0815d..dbbad253a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -50,6 +50,7 @@ namespace mapcontrol mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); +// setCacheMode(QGraphicsItem::ItemCoordinateCache); } UAVItem::~UAVItem() { @@ -233,15 +234,23 @@ namespace mapcontrol //Last thing to do: set bound rectangle as function of largest object - boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+10; //Largest object is currently the biggest ring + a little bit of margin for the text + boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; //Largest object is currently the biggest ring + a little bit of margin for the text } QRectF UAVItem::boundingRect()const { - if(showUAVInfo || showJustChanged) - return QRectF(-boundingRectSize,-boundingRectSize,2*boundingRectSize,2*boundingRectSize); - else + if(showUAVInfo || showJustChanged){ + if (boundingRectSize < 220){ + //In case the bounding rectangle isn't big enough to get the whole of the UAV Info graphic + return QRectF(-boundingRectSize,-80,boundingRectSize+220,180); + } + else{ + return QRectF(-boundingRectSize,-boundingRectSize,2*boundingRectSize,2*boundingRectSize); + } + } + else{ return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); + } } void UAVItem::SetNED(double NED[3]){ From e648a778db0da0d31a596f7d97fe291f7e10df10 Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Fri, 17 Aug 2012 11:51:50 +0200 Subject: [PATCH 083/116] Enabled caching for map widget. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 1 + .../src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index d05b612a9..93a4aa113 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -39,6 +39,7 @@ namespace mapcontrol this->setZValue(4); coord=internals::PointLatLng(50,50); RefreshToolTip(); + setCacheMode(QGraphicsItem::DeviceCoordinateCache); } void HomeItem::RefreshToolTip() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 494482283..ea9653fa1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -45,6 +45,7 @@ namespace mapcontrol connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh())); connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); //resize(); + setCacheMode(QGraphicsItem::ItemCoordinateCache); } void MapGraphicItem::start() From 34efc4d3b7e1476327381bbb2232c117a231ffa6 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Fri, 17 Aug 2012 16:47:11 +0200 Subject: [PATCH 084/116] Dramatic performance gains by turning on caching for homeitem and mapgraphicitem. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 1 + .../src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp | 2 ++ .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 1 - 3 files changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index d05b612a9..93a4aa113 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -39,6 +39,7 @@ namespace mapcontrol this->setZValue(4); coord=internals::PointLatLng(50,50); RefreshToolTip(); + setCacheMode(QGraphicsItem::DeviceCoordinateCache); } void HomeItem::RefreshToolTip() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 494482283..7cabdff56 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -44,6 +44,8 @@ namespace mapcontrol connect(core,SIGNAL(OnNeedInvalidation()),this,SLOT(Core_OnNeedInvalidation())); connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh())); connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); + setCacheMode(QGraphicsItem::ItemCoordinateCache); + //resize(); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index dbbad253a..b1ee0d1e2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -50,7 +50,6 @@ namespace mapcontrol mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); -// setCacheMode(QGraphicsItem::ItemCoordinateCache); } UAVItem::~UAVItem() { From c484dcb1db015bfa10d804f07eb0e46019c41353 Mon Sep 17 00:00:00 2001 From: Kenz Dale Date: Fri, 17 Aug 2012 17:26:15 +0200 Subject: [PATCH 085/116] Corrected mathematics for estimating rate of turn. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 155e0a741..1bd3a18eb 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -52,6 +52,7 @@ #include "homelocation.h" #include "gpsposition.h" #include "gyros.h" +#include "attitudeactual.h" #include "positionactual.h" #include "velocityactual.h" @@ -583,6 +584,7 @@ void OPMapGadgetWidget::updatePosition() //********************** // get the current position and heading estimates + AttitudeActual *attitudeActualObj = AttitudeActual::GetInstance(obm); PositionActual *positionActualObj = PositionActual::GetInstance(obm); VelocityActual *velocityActualObj = VelocityActual::GetInstance(obm); Gyros *gyrosObj = Gyros::GetInstance(obm); @@ -591,6 +593,7 @@ void OPMapGadgetWidget::updatePosition() Q_ASSERT(velocityActualObj); Q_ASSERT(gyrosObj); + AttitudeActual::DataFields attitudeActualData = attitudeActualObj->getData(); PositionActual::DataFields positionActualData = positionActualObj->getData(); VelocityActual::DataFields velocityActualData = velocityActualObj->getData(); Gyros::DataFields gyrosData = gyrosObj->getData(); @@ -602,7 +605,12 @@ void OPMapGadgetWidget::updatePosition() m_map->UAV->SetNED(NED); m_map->UAV->SetCAS(-1); //THIS NEEDS TO BECOME AIRSPEED, ONCE WE SETTLE ON A UAVO m_map->UAV->SetGroundspeed(vNED); - m_map->UAV->SetYawRate(gyrosData.z); //Not correct, but I'm being lazy right now. + + //Convert angular velocities into a rotationg rate around the world-frame yaw axis. This is found by simply taking the dot product of the angular Euler-rate matrix with the angular rates. + float psiRate_dps=0*gyrosData.z + sin(attitudeActualData.Roll*deg_to_rad)/cos(attitudeActualData.Pitch*deg_to_rad)*gyrosData.y + cos(attitudeActualData.Roll*deg_to_rad)/cos(attitudeActualData.Pitch*deg_to_rad)*gyrosData.z; + + //Set the angular rate in the painter module + m_map->UAV->SetYawRate(psiRate_dps); //Not correct, but I'm being lazy right now. // ************* // display the UAV position From 28f382d472c5005eeef11ea8d82b763efbc12d3f Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sat, 18 Aug 2012 09:15:55 +0200 Subject: [PATCH 086/116] Disabled dragging and dropping of UAV and Home icons. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 4 ++-- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 93a4aa113..aa7af3129 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -32,8 +32,8 @@ namespace mapcontrol pic.load(QString::fromUtf8(":/markers/images/home2.svg")); pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); + this->setFlag(QGraphicsItem::ItemIsMovable,false); + this->setFlag(QGraphicsItem::ItemIsSelectable,false); localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index b1ee0d1e2..6937382a1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -37,8 +37,8 @@ namespace mapcontrol ,autosetdistance(100),altitude(0),showUAVInfo(false),showJustChanged(false) { pic.load(uavPic); - this->setFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); + this->setFlag(QGraphicsItem::ItemIsMovable,false); + this->setFlag(QGraphicsItem::ItemIsSelectable,false); localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); this->setPos(localposition.X(),localposition.Y()); this->setZValue(4); From d3daa067134095d3d9576b9b78b0a9d132286846 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sat, 18 Aug 2012 09:19:59 +0200 Subject: [PATCH 087/116] Improved filtered groundspeed calculation. Now the filtering rise time no longer on the refresh rate. --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 21 +++++++++++++++---- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- 3 files changed, 19 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 6937382a1..3c0c13037 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -146,9 +146,7 @@ namespace mapcontrol //*********** Create time rings double ringTime=10*pow(2,17-map->ZoomTotal()); //Basic ring is 10 seconds wide at zoom level 17 - double alpha= .05; - groundspeed_mps_filt= (1-alpha)*groundspeed_mps_filt + alpha*groundspeed_mps; - if(groundspeed_mps > 0){ //Don't clutter the display with rings that are only one pixel wide + if(groundspeed_mps_filt > 0){ //Don't clutter the display with rings that are only one pixel wide myPen.setWidth(2); myPen.setColor(QColor(0, 0, 0, 100)); @@ -274,11 +272,26 @@ namespace mapcontrol this->CAS_mps=CAS_mps; } - void UAVItem::SetGroundspeed(double vNED[3]){ + void UAVItem::SetGroundspeed(double vNED[3], int m_maxUpdateRate_ms){ this->vNED[0] = vNED[0]; this->vNED[1] = vNED[1]; this->vNED[2] = vNED[2]; groundspeed_kph=sqrt(vNED[0]*vNED[0] + vNED[1]*vNED[1] + vNED[2]*vNED[2])*3.6; + + //On the first pass, set the filtered speed to the reported speed. + static bool firstGroundspeed=true; + if (firstGroundspeed){ + groundspeed_mps_filt=groundspeed_kph/3.6; + firstGroundspeed=false; + } + else{ + int riseTime_ms=1000; + double alpha= m_maxUpdateRate_ms/(double)(m_maxUpdateRate_ms+riseTime_ms); + groundspeed_mps_filt= alpha*groundspeed_mps_filt + (1-alpha)*(groundspeed_kph/3.6); + } + + + refreshPaint_flag=true; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 155f61581..263a99930 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -69,7 +69,7 @@ namespace mapcontrol * * @param NED */ - void SetGroundspeed(double vNED[3]); + void SetGroundspeed(double vNED[3], int m_maxUpdateRate); /** * @brief Sets the UAV Calibrated Airspeed * diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 1bd3a18eb..9c796d651 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -604,7 +604,7 @@ void OPMapGadgetWidget::updatePosition() //Set the position and heading estimates in the painter module m_map->UAV->SetNED(NED); m_map->UAV->SetCAS(-1); //THIS NEEDS TO BECOME AIRSPEED, ONCE WE SETTLE ON A UAVO - m_map->UAV->SetGroundspeed(vNED); + m_map->UAV->SetGroundspeed(vNED, m_maxUpdateRate); //Convert angular velocities into a rotationg rate around the world-frame yaw axis. This is found by simply taking the dot product of the angular Euler-rate matrix with the angular rates. float psiRate_dps=0*gyrosData.z + sin(attitudeActualData.Roll*deg_to_rad)/cos(attitudeActualData.Pitch*deg_to_rad)*gyrosData.y + cos(attitudeActualData.Roll*deg_to_rad)/cos(attitudeActualData.Pitch*deg_to_rad)*gyrosData.z; From 375ecfb3695548ea471a3ef8159db3177baab3c4 Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sat, 18 Aug 2012 09:23:09 +0200 Subject: [PATCH 088/116] Streamlined paint function. --- .../opmapcontrol/src/mapwidget/uavitem.cpp | 177 ++++++++++-------- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 8 + 2 files changed, 107 insertions(+), 78 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 3c0c13037..ac100e25d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -50,6 +50,8 @@ namespace mapcontrol mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); + + generateArrowhead(); } UAVItem::~UAVItem() { @@ -64,7 +66,7 @@ namespace mapcontrol //Draw plane painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); - //Return if context menu switch for UAV info is off + //Return if UAV Info context menu is turned off if(!showUAVInfo){ showJustChanged=false; return; @@ -75,46 +77,19 @@ namespace mapcontrol //Turn on anti-aliasing so the fonts don't look terrible painter->setRenderHint(QPainter::Antialiasing, true); - qreal arrowSize = 10; - //Set pen attributes QColor myColor(Qt::red); myPen.setWidth(3); myPen.setColor(myColor); painter->setPen(myPen); - - //Create line from (0,0), to (1,1). Later, we'll scale and rotate it - QLineF line(0,0,1.0,1.0); - - //Set the starting point to (0,0) - line.setP1(QPointF(0,0)); - - //Set angle and length - line.setLength(60.0); - line.setAngle(90.0); - - //Form arrowhead - double angle = ::acos(line.dx() / line.length()); - if (line.dy() <= 0) - angle = (M_PI * 2) - angle; - - QPointF arrowP1 = line.pointAt(1) + QPointF(sin(angle + M_PI / 3) * arrowSize, - cos(angle + M_PI / 3) * arrowSize); - QPointF arrowP2 = line.pointAt(1) + QPointF(sin(angle + M_PI - M_PI / 3) * arrowSize, - cos(angle + M_PI - M_PI / 3) * arrowSize); - - //Generate arrowhead - arrowHead.clear(); - arrowHead << line.pointAt(1) << arrowP1 << arrowP2; painter->drawPolygon(arrowHead); painter->setPen(myPen); - painter->drawLine(line); + painter->drawLine(arrowShaft); //*********** Create trend arc double radius; double spanAngle = yawRate_dps * 5; //Forecast 5 seconds into the future - //Find the scale factor between meters and pixels double pixels2meters = map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); float meters2pixels=1.0 / pixels2meters; @@ -164,56 +139,66 @@ namespace mapcontrol //***** Text info overlay. The font is a "glow" font, so that it's easier to use on the map + if (refreshPaint_flag==true){ + + //Define font + QFont borderfont( "Arial", 14, QFont::Normal, false ); + + //Top left corner of text + int textAnchorX = 20; + int textAnchorY = 20; + + //Create text lines + QString uavoInfoStrLine1, uavoInfoStrLine2; + QString uavoInfoStrLine3, uavoInfoStrLine4; + QString uavoInfoStrLine5; + + //For whatever reason, Qt does not let QPainterPath have text wrapping. So each line of + //text has to be added to a different line. + uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); + uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1)); + uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7)); + uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); + uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); + + //Add the uavo info text to the path + //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. + path = QPainterPath(); + + path.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); + path.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); + path.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); + path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); + path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); + + //Add text for time rings. + if(groundspeed_mps > 0){ + //Always add the left side... + path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + //... and add the right side, only if it doesn't interfere with the uav info text + if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ + path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + } + path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + } + path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + } + } + + //Last thing to do: set bound rectangle as function of largest object + boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; //Largest object is currently the biggest ring + a little bit of margin for the text + + refreshPaint_flag=false; + } + //Rotate the text back to vertical qreal rot=this->rotation(); painter->rotate(-1*rot); - //Define font - QFont borderfont( "Arial", 14, QFont::Normal, false ); - - //Top left corner of text - int textAnchorX = 20; - int textAnchorY = 20; - - //Create text lines - QString uavoInfoStrLine1, uavoInfoStrLine2; - QString uavoInfoStrLine3, uavoInfoStrLine4; - QString uavoInfoStrLine5; - - //For whatever reason, Qt does not let QPainterPath have text wrapping. So each line of - //text has to be added to a different line. - uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); - uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1)); - uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7)); - uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); - uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); - - //Add the uavo info text to the path - //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. - QPainterPath path; - path.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); - path.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); - path.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); - path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); - path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); - - //Add text for time rings. - if(groundspeed_mps > 0){ - //Always add the left side... - path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); - //... and add the right side, only if it doesn't interfere with the uav info text - if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ - path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); - } - path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); - } - path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); - } - } //Now draw the text. First pass is the outline... myPen.setWidth(4); @@ -229,9 +214,6 @@ namespace mapcontrol painter->setPen(myPen); painter->drawPath(path); - - //Last thing to do: set bound rectangle as function of largest object - boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; //Largest object is currently the biggest ring + a little bit of margin for the text } QRectF UAVItem::boundingRect()const @@ -254,6 +236,8 @@ namespace mapcontrol this->NED[0] = NED[0]; this->NED[1] = NED[1]; this->NED[2] = NED[2]; + + refreshPaint_flag=true; } void UAVItem::SetYawRate(double yawRate_dps){ @@ -266,10 +250,13 @@ namespace mapcontrol this->yawRate_dps=5e-1; } + refreshPaint_flag=true; } void UAVItem::SetCAS(double CAS_mps){ this->CAS_mps=CAS_mps; + + refreshPaint_flag=true; } void UAVItem::SetGroundspeed(double vNED[3], int m_maxUpdateRate_ms){ @@ -371,6 +358,8 @@ namespace mapcontrol } } + + refreshPaint_flag=true; } /** @@ -387,6 +376,8 @@ namespace mapcontrol if (this->rotation() != value) this->setRotation(value); } + + refreshPaint_flag=true; } @@ -413,7 +404,9 @@ namespace mapcontrol ww->setLine(map->FromLatLngToLocal(ww->coord1).X(),map->FromLatLngToLocal(ww->coord1).Y(),map->FromLatLngToLocal(ww->coord2).X(),map->FromLatLngToLocal(ww->coord2).Y()); } + refreshPaint_flag=true; } + void UAVItem::SetTrailType(const UAVTrailType::Types &value) { trailtype=value; @@ -455,4 +448,32 @@ namespace mapcontrol update(); } + void UAVItem::generateArrowhead(){ + qreal arrowSize = 10; + + //Create line from (0,0), to (1,1). Later, we'll scale and rotate it + arrowShaft=QLineF(0,0,1.0,1.0); + + //Set the starting point to (0,0) + arrowShaft.setP1(QPointF(0,0)); + + //Set angle and length + arrowShaft.setLength(60.0); + arrowShaft.setAngle(90.0); + + //Form arrowhead + double angle = ::acos(arrowShaft.dx() / arrowShaft.length()); + if (arrowShaft.dy() <= 0) + angle = (M_PI * 2) - angle; + + QPointF arrowP1 = arrowShaft.pointAt(1) + QPointF(sin(angle + M_PI / 3) * arrowSize, + cos(angle + M_PI / 3) * arrowSize); + QPointF arrowP2 = arrowShaft.pointAt(1) + QPointF(sin(angle + M_PI - M_PI / 3) * arrowSize, + cos(angle + M_PI - M_PI / 3) * arrowSize); + + //Assemble arrowhead + arrowHead.clear(); + arrowHead << arrowShaft.pointAt(1) << arrowP1 << arrowP2; + + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 263a99930..eb7303015 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -221,8 +221,11 @@ namespace mapcontrol void SetShowUAVInfo(bool const& value); private: + void generateArrowhead(); + MapGraphicItem* map; QPolygonF arrowHead; + QLineF arrowShaft; int altitude; UAVMapFollowType::Types mapfollowtype; UAVTrailType::Types trailtype; @@ -252,6 +255,11 @@ namespace mapcontrol float boundingRectSize; bool showJustChanged; + bool refreshPaint_flag; + + QPainterPath path; + + public slots: signals: From b7298f890fdc0e27a4f17da28eccd7944f29319f Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sat, 18 Aug 2012 09:28:30 +0200 Subject: [PATCH 089/116] homeitem.cpp fixed to erase the safe area when turning off ShowSafeArea. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 8 ++++++-- .../src/libs/opmapcontrol/src/mapwidget/homeitem.h | 2 ++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 12 +++++++----- 3 files changed, 15 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index aa7af3129..e33645f6b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -27,7 +27,8 @@ #include "homeitem.h" namespace mapcontrol { - HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent),showsafearea(true),safearea(1000),altitude(0),isDragging(false) + HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent), + showsafearea(true),safearea(1000),altitude(0),isDragging(false),toggleRefresh(true) { pic.load(QString::fromUtf8(":/markers/images/home2.svg")); pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); @@ -68,7 +69,7 @@ namespace mapcontrol } QRectF HomeItem::boundingRect()const { - if(pic.width()>localsafearea*2) + if(pic.width()>localsafearea*2 && !toggleRefresh) return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); else return QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2); @@ -90,6 +91,9 @@ namespace mapcontrol RefreshToolTip(); + this->update(); + toggleRefresh=false; + } void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index c3bdd4f3f..6f4804a0b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -50,6 +50,7 @@ namespace mapcontrol void RefreshPos(); bool ShowSafeArea()const{return showsafearea;} void SetShowSafeArea(bool const& value){showsafearea=value;} + void SetToggleRefresh(bool const& value){toggleRefresh=value;} int SafeArea()const{return safearea;} void SetSafeArea(int const& value){safearea=value;} bool safe; @@ -66,6 +67,7 @@ namespace mapcontrol core::Point localposition; internals::PointLatLng coord; bool showsafearea; + bool toggleRefresh; int safearea; int localsafearea; float altitude; diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 9c796d651..8a3d8426f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -104,7 +104,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map_mode = Normal_MapMode; - m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds + m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds //SHOULDN'T THIS BE LOADED FROM THE USER PREFERENCES? m_telemetry_connected = false; @@ -166,8 +166,9 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->SetShowHome(true); // display the HOME position on the map m_map->SetShowUAV(true); // display the UAV position on the map - m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) - m_map->Home->SetShowSafeArea(true); // show the safe area + m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) //SHOULDN'T THE DEFAULT BE USER DEFINED? + m_map->Home->SetShowSafeArea(true); // show the safe area //SHOULDN'T THE DEFAULT BE USER DEFINED? + m_map->Home->SetToggleRefresh(true); if(m_map->Home) connect(m_map->Home,SIGNAL(homedoubleclick(HomeItem*)),this,SLOT(onHomeDoubleClick(HomeItem*))); @@ -540,8 +541,8 @@ void OPMapGadgetWidget::closeEvent(QCloseEvent *event) // timer signals /** - Updates the UAV position on the map. It is called every 200ms - by a timer. + Updates the UAV position on the map. It is called at a user-defined frequency, + as set inside the map widget. */ void OPMapGadgetWidget::updatePosition() { @@ -1875,6 +1876,7 @@ void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show) return; m_map->Home->SetShowSafeArea(show); // show the safe area + m_map->Home->SetToggleRefresh(true); m_map->Home->RefreshPos(); } From ca4fbd5102a742132369da9f7a62e3c26423730f Mon Sep 17 00:00:00 2001 From: Laura Sebesta Date: Sat, 18 Aug 2012 14:18:10 +0200 Subject: [PATCH 090/116] Fixed several compile warning complaints. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp | 6 ++++-- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 5 +++-- .../src/libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 6 +++--- .../config/cfg_vehicletypes/configgroundvehiclewidget.cpp | 8 ++++---- .../config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 +- .../src/plugins/config/configoutputwidget.cpp | 2 +- .../openpilotgcs/src/plugins/config/configrevowidget.cpp | 4 ++-- .../src/plugins/config/configvehicletypewidget.cpp | 2 +- .../src/plugins/gpsdisplay/telemetryparser.cpp | 2 +- .../src/plugins/ipconnection/ipconnectionplugin.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp | 1 + .../openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- .../openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp | 2 +- ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp | 6 +++--- .../src/plugins/uavobjectutil/uavobjectutilmanager.cpp | 4 ++-- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 2 +- ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp | 2 +- ground/openpilotgcs/src/plugins/uploader/SSP/port.h | 2 +- 20 files changed, 34 insertions(+), 30 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index e33645f6b..77ff3d630 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -28,7 +28,7 @@ namespace mapcontrol { HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent), - showsafearea(true),safearea(1000),altitude(0),isDragging(false),toggleRefresh(true) + showsafearea(true),toggleRefresh(true),safearea(1000),altitude(0),isDragging(false) { pic.load(QString::fromUtf8(":/markers/images/home2.svg")); pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 54cc1e575..419b52a0c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -34,7 +34,7 @@ namespace mapcontrol { OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0) - ,followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0),overlayOpacity(1) + ,followmouse(true),compass(0),showuav(false),showhome(false),diagTimer(0),diagGraphItem(0),showDiag(false),overlayOpacity(1) { setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); core=new internals::Core; @@ -392,7 +392,7 @@ namespace mapcontrol } void OPMapWidget::WPDeleteAll() { - int x=0; +// int x=0; foreach(QGraphicsItem* i,map->childItems()) { WayPointItem* w=qgraphicsitem_cast(i); @@ -419,7 +419,9 @@ namespace mapcontrol } } } + return false; } + void OPMapWidget::deleteAllOverlays() { foreach(QGraphicsItem* i,map->childItems()) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index ac100e25d..753e285a2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -33,8 +33,9 @@ namespace mapcontrol double UAVItem::groundspeed_mps_filt = 0; - UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100),altitude(0),showUAVInfo(false),showJustChanged(false) + UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent) + ,altitude(0),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) + ,autosetdistance(100),showUAVInfo(false),showJustChanged(false),refreshPaint_flag(true) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,false); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index eb7303015..b7752acd6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -224,6 +224,7 @@ namespace mapcontrol void generateArrowhead(); MapGraphicItem* map; + OPMapWidget* mapwidget; QPolygonF arrowHead; QLineF arrowShaft; int altitude; @@ -238,7 +239,6 @@ namespace mapcontrol double yawRate_dps; QPixmap pic; core::Point localposition; - OPMapWidget* mapwidget; QGraphicsItemGroup* trail; QGraphicsItemGroup * trailLine; internals::PointLatLng lasttrailline; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index cbb7f94cf..6636c51f4 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -299,7 +299,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) int channel; //disable all - for (channel=0; channelsetupUi(this); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 19047af55..8859468a6 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -109,7 +109,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi //Generate lists of mixerTypeNames, mixerVectorNames, channelNames channelNames << "None"; - for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { + for (unsigned int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { mixerTypes << QString("Mixer%1Type").arg(i+1); mixerVectors << QString("Mixer%1Vector").arg(i+1); diff --git a/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp b/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp index e08d2be52..b0db7f291 100644 --- a/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp +++ b/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp @@ -117,7 +117,7 @@ void TelemetryParser::updateSats( UAVObject* object1) { UAVObjectField* azimuth = object1->getField(QString("Azimuth")); UAVObjectField* snr = object1->getField(QString("SNR")); - for (int i=0;i< prn->getNumElements();i++) { + for (unsigned int i=0;i< prn->getNumElements();i++) { emit satellite(i,prn->getValue(i).toInt(),elevation->getValue(i).toInt(), azimuth->getValue(i).toInt(), snr->getValue(i).toInt()); } diff --git a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp index 5d166584c..78a056378 100644 --- a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp +++ b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp @@ -73,7 +73,7 @@ void IPConnection::onOpenDevice(QString HostName, int Port, bool UseTCP) { QAbstractSocket *ipSocket; const int Timeout = 5 * 1000; - int state; +// int state; ipConMutex.lock(); if (UseTCP) { diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index a1aafb21f..6e4a0d045 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -169,6 +169,7 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const default: return false; } + return false; } QVariant flightDataModel::getColumnByIndex(const pathPlanData *row,const int index) const { diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8a3d8426f..fe2e948d7 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1772,7 +1772,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) if (m_map_mode != Normal_MapMode) return; - float alt=15; + mapProxy->createWayPoint(coord); } diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp index 382c43829..b490f5ddc 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp @@ -315,7 +315,7 @@ int pjrc_rawhid::send(int num, void *buf, int len, int timeout) QString pjrc_rawhid::getserial(int num) { hid_t *hid; - char buf[128]; +// char buf[128]; hid = get_hid(num); diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp index 51fd6cce7..3e661c598 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp @@ -45,8 +45,8 @@ static bool HID_GetStrProperty(IOHIDDeviceRef dev, CFStringRef property, QString */ USBMonitor::USBMonitor(QObject *parent): QThread(parent) { hid_manager=NULL; - CFMutableDictionaryRef dict; - CFNumberRef num; +// CFMutableDictionaryRef dict; +// CFNumberRef num; IOReturn ret; m_instance = this; @@ -131,7 +131,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID { bool got_properties = true; - CFTypeRef prop; +// CFTypeRef prop; USBPortInfo deviceInfo; deviceInfo.dev_handle = dev; diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index a30172fb0..bd30b65a0 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -276,7 +276,7 @@ QByteArray UAVObjectUtilManager::getBoardCPUSerial() QByteArray cpuSerial; FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - for (int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++) + for (unsigned int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++) cpuSerial.append(firmwareIapData.CPUSerial[i]); return cpuSerial; @@ -296,7 +296,7 @@ QByteArray UAVObjectUtilManager::getBoardDescription() QByteArray ret; FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - for (int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++) + for (unsigned int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++) ret.append(firmwareIapData.Description[i]); return ret; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index 7fb8d70c7..ee1623ded 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,7 +32,7 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),allowWidgetUpdates(true),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index 03da96a6f..2e7faff1f 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -449,7 +449,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) default: rxState = STATE_SYNC; stats.rxErrors++; - UAVTALK_QXTLOG_DEBUG("UAVTalk: ???->Sync"); + UAVTALK_QXTLOG_DEBUG("UAVTalk: \?\?\?->Sync"); //Use the escape character for '?' so that the tripgraph isn't triggered. } // Done diff --git a/ground/openpilotgcs/src/plugins/uploader/SSP/port.h b/ground/openpilotgcs/src/plugins/uploader/SSP/port.h index ff4725b99..1521ab412 100644 --- a/ground/openpilotgcs/src/plugins/uploader/SSP/port.h +++ b/ground/openpilotgcs/src/plugins/uploader/SSP/port.h @@ -43,7 +43,7 @@ public: uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet uint16_t max_retry; // Maximum number of retrys for a single transmit. int32_t timeoutLen; // how long to wait for each retry to succeed - int32_t timeout; // current timeout. when 'time' reaches this point we have timed out + uint32_t timeout; // current timeout. when 'time' reaches this point we have timed out uint8_t txSeqNo; // current 'send' packet sequence number uint16_t rxBufPos; // current buffer position in the receive packet uint16_t rxBufLen; // number of 'data' bytes in the buffer From f56b4b8a9bcc9bb823786c43bc213ab727923b2a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 18 Aug 2012 18:07:39 +0100 Subject: [PATCH 091/116] GCS/MapLib - Switched to a signal slot aproach on several functions which need to be propagated. --- .../opmapcontrol/src/mapwidget/gpsitem.cpp | 7 +++ .../libs/opmapcontrol/src/mapwidget/gpsitem.h | 4 +- .../opmapcontrol/src/mapwidget/homeitem.cpp | 7 +++ .../opmapcontrol/src/mapwidget/homeitem.h | 4 +- .../src/mapwidget/mapgraphicitem.cpp | 61 ++----------------- .../src/mapwidget/mapgraphicitem.h | 4 +- .../opmapcontrol/src/mapwidget/uavitem.cpp | 9 +++ .../libs/opmapcontrol/src/mapwidget/uavitem.h | 4 +- .../src/mapwidget/waypointcircle.cpp | 7 +++ .../src/mapwidget/waypointcircle.h | 1 + .../src/mapwidget/waypointitem.cpp | 13 ++++ .../opmapcontrol/src/mapwidget/waypointitem.h | 3 +- .../src/mapwidget/waypointline.cpp | 7 +++ .../opmapcontrol/src/mapwidget/waypointline.h | 1 + 14 files changed, 69 insertions(+), 63 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index 48afa7fbd..862498444 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -45,6 +45,8 @@ namespace mapcontrol mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } GPSItem::~GPSItem() { @@ -139,6 +141,11 @@ namespace mapcontrol } } + + void GPSItem::setOpacitySlot(qreal opacity) + { + setOpacity(opacity); + } void GPSItem::SetTrailType(const UAVTrailType::Types &value) { trailtype=value; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h index 64931ea7f..5ab04b431 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h @@ -103,7 +103,6 @@ namespace mapcontrol void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); - void RefreshPos(); QRectF boundingRect() const; /** * @brief Sets the trail time to be used if TrailType is ByTimeElapsed @@ -218,7 +217,8 @@ namespace mapcontrol // QRectF rect; public slots: - + void RefreshPos(); + void setOpacitySlot(qreal opacity); signals: void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint); void UAVLeftSafetyBouble(internals::PointLatLng const& position); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 93a4aa113..58572f231 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -40,6 +40,8 @@ namespace mapcontrol coord=internals::PointLatLng(50,50); RefreshToolTip(); setCacheMode(QGraphicsItem::DeviceCoordinateCache); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } void HomeItem::RefreshToolTip() @@ -92,6 +94,11 @@ namespace mapcontrol } + void HomeItem::setOpacitySlot(qreal opacity) + { + setOpacity(opacity); + } + void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) { if(event->button()==Qt::LeftButton) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index c3bdd4f3f..50cb48b53 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -47,7 +47,6 @@ namespace mapcontrol QWidget *widget); QRectF boundingRect() const; int type() const; - void RefreshPos(); bool ShowSafeArea()const{return showsafearea;} void SetShowSafeArea(bool const& value){showsafearea=value;} int SafeArea()const{return safearea;} @@ -76,7 +75,8 @@ namespace mapcontrol void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); public slots: - + void RefreshPos(); + void setOpacitySlot(qreal opacity); signals: void homePositionChanged(internals::PointLatLng coord,float); void homedoubleclick(HomeItem* waypoint); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index a0289bfdf..9c627e8c2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -42,8 +42,8 @@ namespace mapcontrol this->SetZoom(2); this->setFlag(ItemIsFocusable); connect(core,SIGNAL(OnNeedInvalidation()),this,SLOT(Core_OnNeedInvalidation())); - connect(core,SIGNAL(OnMapDrag()),this,SLOT(ChildPosRefresh())); - connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(ChildPosRefresh())); + connect(core,SIGNAL(OnMapDrag()),this,SLOT(childPosRefresh())); + connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(childPosRefresh())); setCacheMode(QGraphicsItem::ItemCoordinateCache); //resize(); @@ -82,64 +82,15 @@ namespace mapcontrol void MapGraphicItem::Core_OnNeedInvalidation() { this->update(); - foreach(QGraphicsItem* i,this->childItems()) - { - WayPointItem* w=qgraphicsitem_cast(i); - if(w) - w->RefreshPos(); - UAVItem* ww=qgraphicsitem_cast(i); - if(ww) - ww->RefreshPos(); - HomeItem* www=qgraphicsitem_cast(i); - if(www) - www->RefreshPos(); - GPSItem* wwww=qgraphicsitem_cast(i); - if(wwww) - wwww->RefreshPos(); - } + emit childRefreshPosition(); } - void MapGraphicItem::ChildPosRefresh() + void MapGraphicItem::childPosRefresh() { - foreach(QGraphicsItem* i,this->childItems()) - { - WayPointItem* w=qgraphicsitem_cast(i); - if(w) - w->RefreshPos(); - UAVItem* ww=qgraphicsitem_cast(i); - if(ww) - ww->RefreshPos(); - HomeItem* www=qgraphicsitem_cast(i); - if(www) - www->RefreshPos(); - GPSItem* wwww=qgraphicsitem_cast(i); - if(wwww) - wwww->RefreshPos(); - } + emit childRefreshPosition(); } void MapGraphicItem::setOverlayOpacity(qreal value) { - foreach(QGraphicsItem* i,this->childItems()) - { - WayPointItem* w=qgraphicsitem_cast(i); - if(w) - w->setOpacity(value); - UAVItem* ww=qgraphicsitem_cast(i); - if(ww) - ww->setOpacity(value); - HomeItem* www=qgraphicsitem_cast(i); - if(www) - www->setOpacity(value); - GPSItem* wwww=qgraphicsitem_cast(i); - if(wwww) - wwww->setOpacity(value); - WayPointLine* wwwww=qgraphicsitem_cast(i); - if(wwwww) - wwwww->setOpacity(value); - WayPointCircle* wwwwww=qgraphicsitem_cast(i); - if(wwwwww) - wwwwww->setOpacity(value); - - } + emit childSetOpacity(value); } void MapGraphicItem::ConstructLastImage(int const& zoomdiff) { diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index 1d3ce17f3..06786e222 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -200,7 +200,7 @@ namespace mapcontrol void SetMapType(MapType::Types const& value){core->SetMapType(value);} private slots: void Core_OnNeedInvalidation(); - void ChildPosRefresh(); + void childPosRefresh(); public slots: /** * @brief To be called when the scene size changes @@ -216,6 +216,8 @@ namespace mapcontrol */ void wpdoubleclicked(WayPointItem * wp); void zoomChanged(double zoomtotal,double zoomreal,double zoomdigi); + void childRefreshPosition(); + void childSetOpacity(qreal value); }; } #endif // MAPGRAPHICITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index b1ee0d1e2..5b07f3c6e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -50,6 +50,9 @@ namespace mapcontrol mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); + setCacheMode(QGraphicsItem::DeviceCoordinateCache); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } UAVItem::~UAVItem() { @@ -233,6 +236,7 @@ namespace mapcontrol //Last thing to do: set bound rectangle as function of largest object + prepareGeometryChange(); boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; //Largest object is currently the biggest ring + a little bit of margin for the text } @@ -401,6 +405,11 @@ namespace mapcontrol } } + + void UAVItem::setOpacitySlot(qreal opacity) + { + this->setOpacity(opacity); + } void UAVItem::SetTrailType(const UAVTrailType::Types &value) { trailtype=value; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 155f61581..ef3ade80e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -128,7 +128,6 @@ namespace mapcontrol void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); - void RefreshPos(); QRectF boundingRect() const; /** * @brief Sets the trail time to be used if TrailType is ByTimeElapsed @@ -253,7 +252,8 @@ namespace mapcontrol bool showJustChanged; public slots: - + void RefreshPos(); + void setOpacitySlot(qreal opacity); signals: void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint); void UAVLeftSafetyBouble(internals::PointLatLng const& position); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index c6dfac384..5fc785369 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -38,6 +38,7 @@ WayPointCircle::WayPointCircle(WayPointItem *center, WayPointItem *radius,bool c connect(center,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); connect(radius,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); refreshLocations(); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } @@ -48,6 +49,7 @@ WayPointCircle::WayPointCircle(HomeItem *radius, WayPointItem *center, bool cloc connect(center,SIGNAL(localPositionChanged(QPointF)),this,SLOT(refreshLocations())); connect(center,SIGNAL(aboutToBeDeleted(WayPointItem*)),this,SLOT(waypointdeleted())); refreshLocations(); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } int WayPointCircle::type() const @@ -106,4 +108,9 @@ void WayPointCircle::waypointdeleted() this->deleteLater(); } +void WayPointCircle::setOpacitySlot(qreal opacity) +{ + setOpacity(opacity); +} + } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h index 1c89fb798..4be7b0898 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h @@ -62,6 +62,7 @@ protected: public slots: void refreshLocations(); void waypointdeleted(); + void setOpacitySlot(qreal opacity); }; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 8c7491fe5..1582d03ab 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -60,6 +60,8 @@ WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitu } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(false),description(""),shownumber(true),isDragging(false),altitude(0),map(map) @@ -105,6 +107,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) { @@ -136,6 +140,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals } connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } WayPointItem::WayPointItem(const distBearingAltitude &relativeCoordenate, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoordenate),reached(false),description(description),shownumber(true),isDragging(false),map(map) @@ -169,6 +175,8 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals RefreshPos(); connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } void WayPointItem::setWPType(wptype type) @@ -455,6 +463,11 @@ WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(fals this->setPos(point.X(),point.Y()); emit localPositionChanged(this->pos(),this); } + + void WayPointItem::setOpacitySlot(qreal opacity) + { + setOpacity(opacity); + } void WayPointItem::RefreshToolTip() { QString type_str; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index df5f3b5e9..452eef81e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -156,7 +156,6 @@ public: QRectF boundingRect() const; void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); - void RefreshPos(); void RefreshToolTip(); QPixmap picture; QString customString(){return myCustomString;} @@ -217,6 +216,8 @@ public slots: void WPInserted(int const& number,WayPointItem* waypoint); void onHomePositionChanged(internals::PointLatLng,float altitude); + void RefreshPos(); + void setOpacitySlot(qreal opacity); signals: /** * @brief fires when this WayPoint number changes (not fired if due to a auto-renumbering) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index 7ba3072db..a31c93cbb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -44,6 +44,7 @@ WayPointLine::WayPointLine(WayPointItem *from, WayPointItem *to, MapGraphicItem this->setZValue(9); else if(myColor==Qt::red) this->setZValue(8); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map, QColor color):source(from), @@ -59,6 +60,7 @@ WayPointLine::WayPointLine(HomeItem *from, WayPointItem *to, MapGraphicItem *map this->setZValue(9); else if(myColor==Qt::red) this->setZValue(8); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); } int WayPointLine::type() const { @@ -112,4 +114,9 @@ void WayPointLine::waypointdeleted() this->deleteLater(); } +void WayPointLine::setOpacitySlot(qreal opacity) +{ + setOpacity(opacity); +} + } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h index 6d8985f77..5b7a40f85 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h @@ -60,6 +60,7 @@ protected: public slots: void refreshLocations(); void waypointdeleted(); + void setOpacitySlot(qreal opacity); }; } #endif // WAYPOINTLINE_H From 0afd9237087ef16b6e0bcf50ac38338c3040f5c0 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 18 Aug 2012 20:45:05 +0300 Subject: [PATCH 092/116] CameraStab UI: more comments to serve as a self-documented code sample Also disabled "module enable" checkbox reload/default actions. --- .../configcamerastabilizationwidget.cpp | 36 ++++++++++++------- 1 file changed, 24 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 6defa9a6a..e7d60f018 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configcamerastabilizationwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011-2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -56,16 +56,21 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent // using objrelation dynamic property autoLoadWidgets(); - QList reloadGroups; - reloadGroups<<1; - // Add some widgets and UAVObjects to track widget dirty state - // and monitor UAVObject changes in addition to autoloaded ones + // Add some widgets to track their UI dirty state and handle smartsave addWidget(m_camerastabilization->enableCameraStabilization); addWidget(m_camerastabilization->rollChannel); addWidget(m_camerastabilization->pitchChannel); addWidget(m_camerastabilization->yawChannel); - addUAVObject("HwSettings",&reloadGroups); - addUAVObject("MixerSettings",&reloadGroups); + + // Add some UAVObjects to monitor their changes in addition to autoloaded ones. + // Note also that we want to reload some UAVObjects by "Reload" button and have + // to pass corresponding reload group numbers (defined also in objrelation property) + // to the montitor. We don't reload HwSettings (module enable state) but reload + // output channels. + QList reloadGroups; + reloadGroups << 1; + addUAVObject("HwSettings"); + addUAVObject("MixerSettings", &reloadGroups); // To set special widgets to defaults when requested connect(this, SIGNAL(defaultRequested(int)), this, SLOT(defaultRequestedSlot(int))); @@ -228,12 +233,19 @@ void ConfigCameraStabilizationWidget::defaultRequestedSlot(int group) { Q_UNUSED(group); - HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); - HwSettings *hwSettingsDefault=(HwSettings*)hwSettings->dirtyClone(); - HwSettings::DataFields hwSettingsData = hwSettingsDefault->getData(); - m_camerastabilization->enableCameraStabilization->setChecked( - hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); + // Here is the example of how to reset the state of QCheckBox. It is + // commented out because we normally don't want to reset the module + // enable state to default "disabled" (or we don't care about values at all). + // But if you want, you could use the dirtyClone() function to get default + // values of an object and then use them to set a widget state. + // + //HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + //HwSettings *hwSettingsDefault=(HwSettings*)hwSettings->dirtyClone(); + //HwSettings::DataFields hwSettingsData = hwSettingsDefault->getData(); + //m_camerastabilization->enableCameraStabilization->setChecked( + // hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); + // For outputs we set them all to none, so don't use any UAVObject to get defaults QComboBox *outputs[] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, From 2a4c54a0731b93fa5dcc92558259d0cb05ca854d Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 18 Aug 2012 20:09:04 +0100 Subject: [PATCH 093/116] Revert "Fixed several compile warning complaints." These touch much more than the map lib and plugin so they should be base on next and sent for review This reverts commit ca4fbd5102a742132369da9f7a62e3c26423730f. --- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp | 6 ++---- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 5 ++--- .../src/libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 6 +++--- .../config/cfg_vehicletypes/configgroundvehiclewidget.cpp | 8 ++++---- .../config/cfg_vehicletypes/configmultirotorwidget.cpp | 2 +- .../src/plugins/config/configoutputwidget.cpp | 2 +- .../openpilotgcs/src/plugins/config/configrevowidget.cpp | 4 ++-- .../src/plugins/config/configvehicletypewidget.cpp | 2 +- .../src/plugins/gpsdisplay/telemetryparser.cpp | 2 +- .../src/plugins/ipconnection/ipconnectionplugin.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp | 1 - .../openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- .../openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp | 2 +- ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp | 6 +++--- .../src/plugins/uavobjectutil/uavobjectutilmanager.cpp | 4 ++-- .../src/plugins/uavobjectwidgetutils/configtaskwidget.cpp | 2 +- ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp | 2 +- ground/openpilotgcs/src/plugins/uploader/SSP/port.h | 2 +- 20 files changed, 30 insertions(+), 34 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 7ca0d033b..22f5062e3 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -28,7 +28,7 @@ namespace mapcontrol { HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent), - showsafearea(true),toggleRefresh(true),safearea(1000),altitude(0),isDragging(false) + showsafearea(true),safearea(1000),altitude(0),isDragging(false),toggleRefresh(true) { pic.load(QString::fromUtf8(":/markers/images/home2.svg")); pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 419b52a0c..54cc1e575 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -34,7 +34,7 @@ namespace mapcontrol { OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0) - ,followmouse(true),compass(0),showuav(false),showhome(false),diagTimer(0),diagGraphItem(0),showDiag(false),overlayOpacity(1) + ,followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0),overlayOpacity(1) { setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); core=new internals::Core; @@ -392,7 +392,7 @@ namespace mapcontrol } void OPMapWidget::WPDeleteAll() { -// int x=0; + int x=0; foreach(QGraphicsItem* i,map->childItems()) { WayPointItem* w=qgraphicsitem_cast(i); @@ -419,9 +419,7 @@ namespace mapcontrol } } } - return false; } - void OPMapWidget::deleteAllOverlays() { foreach(QGraphicsItem* i,map->childItems()) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 3870596a0..b80ce2c31 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -33,9 +33,8 @@ namespace mapcontrol double UAVItem::groundspeed_mps_filt = 0; - UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent) - ,altitude(0),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100),showUAVInfo(false),showJustChanged(false),refreshPaint_flag(true) + UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) + ,autosetdistance(100),altitude(0),showUAVInfo(false),showJustChanged(false) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,false); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index bc063f0fc..a135d9685 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -223,7 +223,6 @@ namespace mapcontrol void generateArrowhead(); MapGraphicItem* map; - OPMapWidget* mapwidget; QPolygonF arrowHead; QLineF arrowShaft; int altitude; @@ -238,6 +237,7 @@ namespace mapcontrol double yawRate_dps; QPixmap pic; core::Point localposition; + OPMapWidget* mapwidget; QGraphicsItemGroup* trail; QGraphicsItemGroup * trailLine; internals::PointLatLng lasttrailline; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 6636c51f4..cbb7f94cf 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -299,7 +299,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) int channel; //disable all - for (channel=0; (unsigned int) channelsetupUi(this); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 8859468a6..19047af55 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -109,7 +109,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi //Generate lists of mixerTypeNames, mixerVectorNames, channelNames channelNames << "None"; - for (unsigned int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { + for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { mixerTypes << QString("Mixer%1Type").arg(i+1); mixerVectors << QString("Mixer%1Vector").arg(i+1); diff --git a/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp b/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp index b0db7f291..e08d2be52 100644 --- a/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp +++ b/ground/openpilotgcs/src/plugins/gpsdisplay/telemetryparser.cpp @@ -117,7 +117,7 @@ void TelemetryParser::updateSats( UAVObject* object1) { UAVObjectField* azimuth = object1->getField(QString("Azimuth")); UAVObjectField* snr = object1->getField(QString("SNR")); - for (unsigned int i=0;i< prn->getNumElements();i++) { + for (int i=0;i< prn->getNumElements();i++) { emit satellite(i,prn->getValue(i).toInt(),elevation->getValue(i).toInt(), azimuth->getValue(i).toInt(), snr->getValue(i).toInt()); } diff --git a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp index 78a056378..5d166584c 100644 --- a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp +++ b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionplugin.cpp @@ -73,7 +73,7 @@ void IPConnection::onOpenDevice(QString HostName, int Port, bool UseTCP) { QAbstractSocket *ipSocket; const int Timeout = 5 * 1000; -// int state; + int state; ipConMutex.lock(); if (UseTCP) { diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index 6e4a0d045..a1aafb21f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -169,7 +169,6 @@ bool flightDataModel::setColumnByIndex(pathPlanData *row,const int index,const default: return false; } - return false; } QVariant flightDataModel::getColumnByIndex(const pathPlanData *row,const int index) const { diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index fe2e948d7..8a3d8426f 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1772,7 +1772,7 @@ void OPMapGadgetWidget::onAddWayPointAct_triggered(internals::PointLatLng coord) if (m_map_mode != Normal_MapMode) return; - + float alt=15; mapProxy->createWayPoint(coord); } diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp index b490f5ddc..382c43829 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp @@ -315,7 +315,7 @@ int pjrc_rawhid::send(int num, void *buf, int len, int timeout) QString pjrc_rawhid::getserial(int num) { hid_t *hid; -// char buf[128]; + char buf[128]; hid = get_hid(num); diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp index 3e661c598..51fd6cce7 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp @@ -45,8 +45,8 @@ static bool HID_GetStrProperty(IOHIDDeviceRef dev, CFStringRef property, QString */ USBMonitor::USBMonitor(QObject *parent): QThread(parent) { hid_manager=NULL; -// CFMutableDictionaryRef dict; -// CFNumberRef num; + CFMutableDictionaryRef dict; + CFNumberRef num; IOReturn ret; m_instance = this; @@ -131,7 +131,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID { bool got_properties = true; -// CFTypeRef prop; + CFTypeRef prop; USBPortInfo deviceInfo; deviceInfo.dev_handle = dev; diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index bd30b65a0..a30172fb0 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -276,7 +276,7 @@ QByteArray UAVObjectUtilManager::getBoardCPUSerial() QByteArray cpuSerial; FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - for (unsigned int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++) + for (int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++) cpuSerial.append(firmwareIapData.CPUSerial[i]); return cpuSerial; @@ -296,7 +296,7 @@ QByteArray UAVObjectUtilManager::getBoardDescription() QByteArray ret; FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap(); - for (unsigned int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++) + for (int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++) ret.append(firmwareIapData.Description[i]); return ret; diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index ee1623ded..7fb8d70c7 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -32,7 +32,7 @@ /** * Constructor */ -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),allowWidgetUpdates(true),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false),outOfLimitsStyle("background-color: rgb(255, 0, 0);"),timeOut(NULL),allowWidgetUpdates(true) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index 2e7faff1f..03da96a6f 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -449,7 +449,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) default: rxState = STATE_SYNC; stats.rxErrors++; - UAVTALK_QXTLOG_DEBUG("UAVTalk: \?\?\?->Sync"); //Use the escape character for '?' so that the tripgraph isn't triggered. + UAVTALK_QXTLOG_DEBUG("UAVTalk: ???->Sync"); } // Done diff --git a/ground/openpilotgcs/src/plugins/uploader/SSP/port.h b/ground/openpilotgcs/src/plugins/uploader/SSP/port.h index 1521ab412..ff4725b99 100644 --- a/ground/openpilotgcs/src/plugins/uploader/SSP/port.h +++ b/ground/openpilotgcs/src/plugins/uploader/SSP/port.h @@ -43,7 +43,7 @@ public: uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet uint16_t max_retry; // Maximum number of retrys for a single transmit. int32_t timeoutLen; // how long to wait for each retry to succeed - uint32_t timeout; // current timeout. when 'time' reaches this point we have timed out + int32_t timeout; // current timeout. when 'time' reaches this point we have timed out uint8_t txSeqNo; // current 'send' packet sequence number uint16_t rxBufPos; // current buffer position in the receive packet uint16_t rxBufLen; // number of 'data' bytes in the buffer From 4b8bfcb997838e3a5c15c448431632f6b7390738 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sat, 18 Aug 2012 23:04:31 +0100 Subject: [PATCH 094/116] GCS/OPMap - Changed several foreach chield methods to signal/slot --- .../opmapcontrol/src/mapwidget/gpsitem.cpp | 35 ++++++++++--------- .../libs/opmapcontrol/src/mapwidget/gpsitem.h | 2 ++ .../src/mapwidget/mapgraphicitem.cpp | 3 +- .../opmapcontrol/src/mapwidget/trailitem.cpp | 8 +++-- .../opmapcontrol/src/mapwidget/trailitem.h | 8 ++--- .../src/mapwidget/traillineitem.cpp | 8 +++-- .../src/mapwidget/traillineitem.h | 8 ++--- .../opmapcontrol/src/mapwidget/uavitem.cpp | 35 ++++++++++--------- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 4 ++- 9 files changed, 60 insertions(+), 51 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index 862498444..6c2bee192 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -74,9 +74,15 @@ namespace mapcontrol { if(timer.elapsed()>trailtime*1000) { - trail->addToGroup(new TrailItem(position,altitude,Qt::green,this)); + TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + trail->addToGroup(ob); + connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) - trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::green,map))); + { + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + trailLine->addToGroup(obj); + connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); + } lasttrailline=position; timer.restart(); } @@ -86,10 +92,15 @@ namespace mapcontrol { if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position)*1000)>traildistance) { - trail->addToGroup(new TrailItem(position,altitude,Qt::green,this)); + TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + trail->addToGroup(ob); + connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) - - trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::green,this))); + { + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + trailLine->addToGroup(obj); + connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); + } lasttrailline=position; lastcoord=position; } @@ -127,18 +138,8 @@ namespace mapcontrol { localposition=map->FromLatLngToLocal(coord); this->setPos(localposition.X(),localposition.Y()); - foreach(QGraphicsItem* i,trail->childItems()) - { - TrailItem* w=qgraphicsitem_cast(i); - if(w) - w->setPos(map->FromLatLngToLocal(w->coord).X(),map->FromLatLngToLocal(w->coord).Y()); - } - foreach(QGraphicsItem* i,trailLine->childItems()) - { - TrailLineItem* ww=qgraphicsitem_cast(i); - if(ww) - ww->setLine(map->FromLatLngToLocal(ww->coord1).X(),map->FromLatLngToLocal(ww->coord1).Y(),map->FromLatLngToLocal(ww->coord2).X(),map->FromLatLngToLocal(ww->coord2).Y()); - } + emit setChildPosition(); + emit setChildLine(); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h index 5ab04b431..22de85c96 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h @@ -222,6 +222,8 @@ namespace mapcontrol signals: void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint); void UAVLeftSafetyBouble(internals::PointLatLng const& position); + void setChildPosition(); + void setChildLine(); }; } #endif // GPSITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 9c627e8c2..3e2cb2b79 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -98,8 +98,7 @@ namespace mapcontrol QSize size=boundingRect().size().toSize(); size.setWidth(size.width()*2*zoomdiff); size.setHeight(size.height()*2*zoomdiff); - temp=QImage(size, - QImage::Format_ARGB32_Premultiplied); + temp=QImage(size,QImage::Format_ARGB32_Premultiplied); temp.fill(0); QPainter imagePainter(&temp); imagePainter.translate(-boundingRect().topLeft()); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp index c9666dff9..0337768ad 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp @@ -28,9 +28,8 @@ #include namespace mapcontrol { - TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, QGraphicsItem* parent):QGraphicsItem(parent),coord(coord) +TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, MapGraphicItem *map):QGraphicsItem(map),coord(coord),m_brush(color),m_map(map) { - m_brush=color; QDateTime time=QDateTime::currentDateTime(); QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); setToolTip(QString(tr("Position:")+"%1\n"+tr("Altitude:")+"%2\n"+tr("Time:")+"%3").arg(coord_str).arg(QString::number(altitude)).arg(time.toString())); @@ -52,5 +51,8 @@ namespace mapcontrol return Type; } - + void TrailItem::setPosSLOT() + { + setPos(m_map->FromLatLngToLocal(this->coord).X(),m_map->FromLatLngToLocal(this->coord).Y()); + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h index 4af8282d5..12cf03c7b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h @@ -32,6 +32,7 @@ #include #include "../internals/pointlatlng.h" #include +#include "mapgraphicitem.h" namespace mapcontrol { @@ -42,7 +43,7 @@ namespace mapcontrol Q_INTERFACES(QGraphicsItem) public: enum { Type = UserType + 3 }; - TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, QGraphicsItem* parent); + TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color,MapGraphicItem * map); void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); QRectF boundingRect() const; @@ -50,10 +51,9 @@ namespace mapcontrol internals::PointLatLng coord; private: QBrush m_brush; - - + MapGraphicItem * m_map; public slots: - + void setPosSLOT(); signals: }; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp index 9dfe5d584..d6353b31b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp @@ -28,9 +28,8 @@ namespace mapcontrol { - TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, QGraphicsItem* parent):QGraphicsLineItem(parent),coord1(coord1),coord2(coord2) +TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, MapGraphicItem * map):QGraphicsLineItem(map),coord1(coord1),coord2(coord2),m_brush(color),m_map(map) { - m_brush=color; QPen pen; pen.setBrush(m_brush); pen.setWidth(1); @@ -42,5 +41,8 @@ namespace mapcontrol return Type; } - + void TrailLineItem::setLineSlot() + { + setLine(m_map->FromLatLngToLocal(this->coord1).X(),m_map->FromLatLngToLocal(this->coord1).Y(),m_map->FromLatLngToLocal(this->coord2).X(),m_map->FromLatLngToLocal(this->coord2).Y()); + } } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h index f5e7ec627..357998153 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h @@ -32,6 +32,7 @@ #include #include "../internals/pointlatlng.h" #include +#include "mapgraphicitem.h" namespace mapcontrol { @@ -42,16 +43,15 @@ namespace mapcontrol Q_INTERFACES(QGraphicsItem) public: enum { Type = UserType + 7 }; - TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, QGraphicsItem* parent); + TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color,MapGraphicItem * map); int type() const; internals::PointLatLng coord1; internals::PointLatLng coord2; private: QBrush m_brush; - - + MapGraphicItem * m_map; public slots: - + void setLineSlot(); signals: }; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index b80ce2c31..740a7a7cb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -297,9 +297,15 @@ namespace mapcontrol { if(timer.elapsed()>trailtime*1000) { - trail->addToGroup(new TrailItem(position,altitude,Qt::red,this)); + TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + trail->addToGroup(ob); + connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) - trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::red,map))); + { + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + trailLine->addToGroup(obj); + connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); + } lasttrailline=position; timer.restart(); } @@ -309,9 +315,15 @@ namespace mapcontrol { if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position)*1000)>traildistance) { - trail->addToGroup(new TrailItem(position,altitude,Qt::red,this)); + TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + trail->addToGroup(ob); + connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) - trailLine->addToGroup((new TrailLineItem(lasttrailline,position,Qt::red,map))); + { + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + trailLine->addToGroup(obj); + connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); + } lasttrailline=position; lastcoord=position; } @@ -395,19 +407,8 @@ namespace mapcontrol { localposition=map->FromLatLngToLocal(coord); this->setPos(localposition.X(),localposition.Y()); - foreach(QGraphicsItem* i,trail->childItems()) - { - TrailItem* w=qgraphicsitem_cast(i); - if(w) - w->setPos(map->FromLatLngToLocal(w->coord).X(),map->FromLatLngToLocal(w->coord).Y()); - } - foreach(QGraphicsItem* i,trailLine->childItems()) - { - TrailLineItem* ww=qgraphicsitem_cast(i); - if(ww) - ww->setLine(map->FromLatLngToLocal(ww->coord1).X(),map->FromLatLngToLocal(ww->coord1).Y(),map->FromLatLngToLocal(ww->coord2).X(),map->FromLatLngToLocal(ww->coord2).Y()); - } - + emit setChildPosition(); + emit setChildLine(); refreshPaint_flag=true; } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index a135d9685..2e33c5985 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -223,6 +223,7 @@ namespace mapcontrol void generateArrowhead(); MapGraphicItem* map; + OPMapWidget* mapwidget; QPolygonF arrowHead; QLineF arrowShaft; int altitude; @@ -237,7 +238,6 @@ namespace mapcontrol double yawRate_dps; QPixmap pic; core::Point localposition; - OPMapWidget* mapwidget; QGraphicsItemGroup* trail; QGraphicsItemGroup * trailLine; internals::PointLatLng lasttrailline; @@ -265,6 +265,8 @@ namespace mapcontrol signals: void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint); void UAVLeftSafetyBouble(internals::PointLatLng const& position); + void setChildPosition(); + void setChildLine(); }; } #endif // UAVITEM_H From 42119f8d67a7353da4218f3230172d312ae059f2 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 19 Aug 2012 01:40:05 +0100 Subject: [PATCH 095/116] GCS/OPMap- UAVItem - removed everything that doesn't belong on the paint function --- .../src/mapwidget/mapgraphicitem.cpp | 3 - .../opmapcontrol/src/mapwidget/uavitem.cpp | 206 ++++++++---------- .../libs/opmapcontrol/src/mapwidget/uavitem.h | 13 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 5 +- 4 files changed, 97 insertions(+), 130 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 3e2cb2b79..2eed323ac 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -45,9 +45,6 @@ namespace mapcontrol connect(core,SIGNAL(OnMapDrag()),this,SLOT(childPosRefresh())); connect(core,SIGNAL(OnMapZoomChanged()),this,SLOT(childPosRefresh())); setCacheMode(QGraphicsItem::ItemCoordinateCache); - - //resize(); - setCacheMode(QGraphicsItem::ItemCoordinateCache); } void MapGraphicItem::start() diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index 740a7a7cb..a06872b0f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -34,7 +34,7 @@ namespace mapcontrol double UAVItem::groundspeed_mps_filt = 0; UAVItem::UAVItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) - ,autosetdistance(100),altitude(0),showUAVInfo(false),showJustChanged(false) + ,autosetdistance(100),altitude(0),showUAVInfo(false) { pic.load(uavPic); this->setFlag(QGraphicsItem::ItemIsMovable,false); @@ -47,14 +47,17 @@ namespace mapcontrol trailLine=new QGraphicsItemGroup(this); trailLine->setParentItem(map); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + setCacheMode(QGraphicsItem::ItemCoordinateCache); mapfollowtype=UAVMapFollowType::None; trailtype=UAVTrailType::ByDistance; timer.start(); - generateArrowhead(); + double pixels2meters = map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); + meters2pixels=1.0 / pixels2meters; setCacheMode(QGraphicsItem::DeviceCoordinateCache); connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); + connect(map,SIGNAL(zoomChanged(double,double,double)),this,SLOT(zoomChangedSlot())); } UAVItem::~UAVItem() { @@ -71,7 +74,6 @@ namespace mapcontrol //Return if UAV Info context menu is turned off if(!showUAVInfo){ - showJustChanged=false; return; } @@ -89,140 +91,99 @@ namespace mapcontrol painter->setPen(myPen); painter->drawLine(arrowShaft); - //*********** Create trend arc - double radius; - double spanAngle = yawRate_dps * 5; //Forecast 5 seconds into the future - - - //Find the scale factor between meters and pixels - double pixels2meters = map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); - float meters2pixels=1.0 / pixels2meters; - - //Calculate radius in [m], and then convert to pixels in local frame (not the same frame as is displayed on the map widget) - double groundspeed_mps=groundspeed_kph/3.6; - radius=fabs(groundspeed_mps/(yawRate_dps*M_PI/180))*meters2pixels; - -// qDebug() << "Scale: " << meters2pixels; -// qDebug() << "Zoom: " << map->ZoomTotal(); -// qDebug()<< "Radius:" << radius; -// qDebug()<< "Span angle:" << spanAngle; - //Set trend arc's color myPen.setColor(Qt::magenta); painter->setPen(myPen); - //Draw arc. Qt is incomprehensibly limited in that it does not let you set a radius and two points, - //so instead it's a hackish approach requiring a rectangle and a span angle - if (spanAngle > 0){ - QRectF rect(0, -radius, radius*2, radius*2); - painter->drawArc(rect, 180*16, -spanAngle*16); + if (trendSpanAngle > 0){ + QRectF rect(0, -trendRadius, trendRadius*2, trendRadius*2); + painter->drawArc(rect, 180*16, -trendSpanAngle*16); } else{ - QRectF rect(-2*radius, -radius, radius*2, radius*2); - painter->drawArc(rect, 0*16, -spanAngle*16); + QRectF rect(-2*trendRadius, -trendRadius, trendRadius*2, trendRadius*2); + painter->drawArc(rect, 0*16, -trendSpanAngle*16); } //*********** Create time rings - double ringTime=10*pow(2,17-map->ZoomTotal()); //Basic ring is 10 seconds wide at zoom level 17 - if(groundspeed_mps_filt > 0){ //Don't clutter the display with rings that are only one pixel wide myPen.setWidth(2); myPen.setColor(QColor(0, 0, 0, 100)); painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*1*meters2pixels,groundspeed_mps_filt*ringTime*1*meters2pixels); + painter->drawEllipse(QPointF(0,0),precalcRings,precalcRings); myPen.setColor(QColor(0, 0, 0, 110)); painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*2*meters2pixels,groundspeed_mps_filt*ringTime*2*meters2pixels); + painter->drawEllipse(QPointF(0,0),precalcRings*2,precalcRings*2); myPen.setColor(QColor(0, 0, 0, 120)); painter->setPen(myPen); - painter->drawEllipse(QPointF(0,0),groundspeed_mps_filt*ringTime*4*meters2pixels,groundspeed_mps_filt*ringTime*4*meters2pixels); + painter->drawEllipse(QPointF(0,0),precalcRings*4,precalcRings*4); } - - //***** Text info overlay. The font is a "glow" font, so that it's easier to use on the map - - if (refreshPaint_flag==true){ - - //Define font - QFont borderfont( "Arial", 14, QFont::Normal, false ); - - //Top left corner of text - int textAnchorX = 20; - int textAnchorY = 20; - - //Create text lines - QString uavoInfoStrLine1, uavoInfoStrLine2; - QString uavoInfoStrLine3, uavoInfoStrLine4; - QString uavoInfoStrLine5; - - //For whatever reason, Qt does not let QPainterPath have text wrapping. So each line of - //text has to be added to a different line. - uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); - uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1)); - uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7)); - uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); - uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); - - //Add the uavo info text to the path - //NOTE: We must use QPainterPath for the outlined text font. QPaint does not support this. - path = QPainterPath(); - - path.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); - path.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); - path.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); - path.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); - path.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); - - //Add text for time rings. - if(groundspeed_mps > 0){ - //Always add the left side... - path.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); - path.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); - //... and add the right side, only if it doesn't interfere with the uav info text - if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ - if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ - path.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); - } - path.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); - } - path.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); - } - } - - //Last thing to do: set bound rectangle as function of largest object - boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; //Largest object is currently the biggest ring + a little bit of margin for the text - - refreshPaint_flag=false; - } - //Rotate the text back to vertical qreal rot=this->rotation(); painter->rotate(-1*rot); - - //Now draw the text. First pass is the outline... - myPen.setWidth(4); - myPen.setColor(Qt::black); - painter->setPen(myPen); - painter->setBrush(Qt::black); - painter->drawPath(path); - - //...second pass is the inlay myPen.setWidth(1); myPen.setColor(Qt::white); painter->setBrush(Qt::white); painter->setPen(myPen); - painter->drawPath(path); + painter->drawPath(textPath); + } + void UAVItem::updateTextOverlay() + { + QPainterPath temp; + if(!showUAVInfo) + { + temp.swap(textPath); + return; + } + + QFont borderfont( "Arial", 14, QFont::Normal, false ); + + //Top left corner of text + int textAnchorX = 20; + int textAnchorY = 20; + + QString uavoInfoStrLine1, uavoInfoStrLine2; + QString uavoInfoStrLine3, uavoInfoStrLine4; + QString uavoInfoStrLine5; + + uavoInfoStrLine1.append(QString("CAS: %1 kph").arg(CAS_mps)); + uavoInfoStrLine2.append(QString("Groundspeed: %1 kph").arg(groundspeed_kph, 0, 'f',1)); + uavoInfoStrLine3.append(QString("Lat-Lon: %1, %2").arg(coord.Lat(), 0, 'f',7).arg(coord.Lng(), 0, 'f',7)); + uavoInfoStrLine4.append(QString("North-East: %1 m, %2 m").arg(NED[0], 0, 'f',1).arg(NED[1], 0, 'f',1)); + uavoInfoStrLine5.append(QString("Altitude: %1 m").arg(-NED[2], 0, 'f',1)); + temp.addText(textAnchorX, textAnchorY+16*0, borderfont, uavoInfoStrLine1); + temp.addText(textAnchorX, textAnchorY+16*1, borderfont, uavoInfoStrLine2); + temp.addText(textAnchorX, textAnchorY+16*2, borderfont, uavoInfoStrLine3); + temp.addText(textAnchorX, textAnchorY+16*3, borderfont, uavoInfoStrLine4); + temp.addText(textAnchorX, textAnchorY+16*4, borderfont, uavoInfoStrLine5); + + //Add text for time rings. + if(groundspeed_mps > 0){ + //Always add the left side... + temp.addText(-(groundspeed_mps_filt*ringTime*1*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + temp.addText(-(groundspeed_mps_filt*ringTime*2*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + temp.addText(-(groundspeed_mps_filt*ringTime*4*meters2pixels+10), 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + //... and add the right side, only if it doesn't interfere with the uav info text + if(groundspeed_mps_filt*ringTime*4*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*2*meters2pixels > 200){ + if(groundspeed_mps_filt*ringTime*1*meters2pixels > 200){ + temp.addText(groundspeed_mps_filt*ringTime*1*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime,0,'f',0)); + } + temp.addText(groundspeed_mps_filt*ringTime*2*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*2,0,'f',0)); + } + temp.addText(groundspeed_mps_filt*ringTime*4*meters2pixels-8, 0, borderfont, QString("%1 s").arg(ringTime*4,0,'f',0)); + } + } + temp.swap(textPath); } QRectF UAVItem::boundingRect()const { - if(showUAVInfo || showJustChanged){ + if(showUAVInfo){ if (boundingRectSize < 220){ //In case the bounding rectangle isn't big enough to get the whole of the UAV Info graphic return QRectF(-boundingRectSize,-80,boundingRectSize+220,180); @@ -240,27 +201,24 @@ namespace mapcontrol this->NED[0] = NED[0]; this->NED[1] = NED[1]; this->NED[2] = NED[2]; - - refreshPaint_flag=true; } void UAVItem::SetYawRate(double yawRate_dps){ this->yawRate_dps=yawRate_dps; - //There is a minimum arc distance under which Qt no longer draws an arc. At this low a turning rate, - //all curves look straight, so the user won't notice the difference. Moreover, our sensors aren't - //accurate enough to reliably describe this low a yaw rate. if (fabs(this->yawRate_dps) < 5e-1){ //This number is really the smallest we can go. Any smaller, and it might have problems if we forecast a shorter distance into the future this->yawRate_dps=5e-1; } - refreshPaint_flag=true; + //*********** Create trend arc + trendSpanAngle = this->yawRate_dps * 5; //Forecast 5 seconds into the future + + //Calculate radius in [m], and then convert to pixels in local frame (not the same frame as is displayed on the map widget) + trendRadius=fabs(groundspeed_mps/(this->yawRate_dps*M_PI/180))*meters2pixels; } void UAVItem::SetCAS(double CAS_mps){ this->CAS_mps=CAS_mps; - - refreshPaint_flag=true; } void UAVItem::SetGroundspeed(double vNED[3], int m_maxUpdateRate_ms){ @@ -268,7 +226,7 @@ namespace mapcontrol this->vNED[1] = vNED[1]; this->vNED[2] = vNED[2]; groundspeed_kph=sqrt(vNED[0]*vNED[0] + vNED[1]*vNED[1] + vNED[2]*vNED[2])*3.6; - + groundspeed_mps=groundspeed_kph/3.6; //On the first pass, set the filtered speed to the reported speed. static bool firstGroundspeed=true; if (firstGroundspeed){ @@ -280,9 +238,10 @@ namespace mapcontrol double alpha= m_maxUpdateRate_ms/(double)(m_maxUpdateRate_ms+riseTime_ms); groundspeed_mps_filt= alpha*groundspeed_mps_filt + (1-alpha)*(groundspeed_kph/3.6); } - - - refreshPaint_flag=true; + ringTime=10*pow(2,17-map->ZoomTotal()); //Basic ring is 10 seconds wide at zoom level 17 + precalcRings=groundspeed_mps_filt*ringTime*meters2pixels; + boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; + prepareGeometryChange(); } @@ -335,7 +294,6 @@ namespace mapcontrol { mapwidget->SetCurrentPosition(coord); } - this->update(); if(autosetreached) { foreach(QGraphicsItem* i,map->childItems()) @@ -374,8 +332,6 @@ namespace mapcontrol } } - - refreshPaint_flag=true; } /** @@ -392,8 +348,6 @@ namespace mapcontrol if (this->rotation() != value) this->setRotation(value); } - - refreshPaint_flag=true; } @@ -409,13 +363,23 @@ namespace mapcontrol this->setPos(localposition.X(),localposition.Y()); emit setChildPosition(); emit setChildLine(); - refreshPaint_flag=true; + updateTextOverlay(); } void UAVItem::setOpacitySlot(qreal opacity) { this->setOpacity(opacity); } + + void UAVItem::zoomChangedSlot() + { + double pixels2meters = map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); + meters2pixels=1.0 / pixels2meters; + boundingRectSize=groundspeed_mps_filt*ringTime*4*meters2pixels+20; + prepareGeometryChange(); + updateTextOverlay(); + update(); + } void UAVItem::SetTrailType(const UAVTrailType::Types &value) { trailtype=value; diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 2e33c5985..2c5657996 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -218,10 +218,9 @@ namespace mapcontrol void SetUavPic(QString UAVPic); void SetShowUAVInfo(bool const& value); - + void updateTextOverlay(); private: void generateArrowhead(); - MapGraphicItem* map; OPMapWidget* mapwidget; QPolygonF arrowHead; @@ -235,7 +234,13 @@ namespace mapcontrol double vNED[3]; double CAS_mps; double groundspeed_kph; + double groundspeed_mps; double yawRate_dps; + double trendRadius; + double trendSpanAngle; + float meters2pixels; + double precalcRings; + double ringTime; QPixmap pic; core::Point localposition; QGraphicsItemGroup* trail; @@ -256,12 +261,12 @@ namespace mapcontrol bool refreshPaint_flag; - QPainterPath path; - + QPainterPath textPath; public slots: void RefreshPos(); void setOpacitySlot(qreal opacity); + void zoomChangedSlot(); signals: void UAVReachedWayPoint(int const& waypointnumber,WayPointItem* waypoint); void UAVLeftSafetyBouble(internals::PointLatLng const& position); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 8a3d8426f..25fd84f3b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -213,7 +213,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_map->SetCurrentPosition(m_home_position.coord); // set the map position m_map->Home->SetCoord(m_home_position.coord); // set the HOME position m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position - + m_map->UAV->update(); if(m_map->GPS) m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the GPS position #ifdef USE_PATHPLANNER @@ -638,7 +638,8 @@ void OPMapGadgetWidget::updatePosition() m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading } - + m_map->UAV->updateTextOverlay(); + m_map->UAV->update(); // ************* } From 83097ecffbfe0aa8776ff7a172d2a6586cdd1928 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 19 Aug 2012 01:43:49 +0100 Subject: [PATCH 096/116] GCS/OPMap- bumped up the QPixmap max cache value --- .../src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 54cc1e575..56084f5c2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -60,7 +60,7 @@ namespace mapcontrol SetShowDiagnostics(showDiag); this->setMouseTracking(followmouse); SetShowCompass(true); - + QPixmapCache::setCacheLimit(64*1024); } void OPMapWidget::SetShowDiagnostics(bool const& value) { From 45e21acefdec56571bc57c6779c15f86b5588c0a Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 19 Aug 2012 14:41:09 +0100 Subject: [PATCH 097/116] GCS- Get rid of the double hwsettings update. setData triggers an update so the other functions should be used instead. MixerSettings should be refactored next. --- .../src/plugins/config/configcamerastabilizationwidget.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index e7d60f018..9c4470a1d 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -153,11 +153,9 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() { // Save state of the module enable checkbox first HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); - HwSettings::DataFields hwSettingsData = hwSettings->getData(); - hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] = - m_camerastabilization->enableCameraStabilization->isChecked() ? + quint8 value = m_camerastabilization->enableCameraStabilization->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; - hwSettings->setData(hwSettingsData); + hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB,value); // Update mixer channels which were mapped to camera outputs in case they are // not used for other function yet From 84d55ca416bd6272df9140ff55bacb264f4f0f41 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Sun, 19 Aug 2012 14:41:57 +0100 Subject: [PATCH 098/116] GCS-Added a few overloaded functions so that object and field pointers can be used with confitaskwidget framework --- .../uavobjectwidgetutils/configtaskwidget.cpp | 42 +++++++++++++++++++ .../uavobjectwidgetutils/configtaskwidget.h | 7 ++++ 2 files changed, 49 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index a947ffe6e..88e7d868a 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -61,6 +61,15 @@ void ConfigTaskWidget::addUAVObject(QString objectName,QList * reloadGroups { addUAVObjectToWidgetRelation(objectName,"",NULL,0,1,false,reloadGroups); } + +void ConfigTaskWidget::addUAVObject(UAVObject *objectName, QList *reloadGroups) +{ + QString objstr; + if(objectName) + objstr=objectName->getName(); + addUAVObject(objstr, reloadGroups); + +} /** * Add an UAVObject field to widget relation to the management system * @param object name of the object to add @@ -78,6 +87,17 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel Q_ASSERT(_field); addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index)); } + +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index) +{ + QString objstr; + QString fieldstr; + if(obj) + objstr=obj->getName(); + if(field) + fieldstr=field->getName(); + addUAVObjectToWidgetRelation(objstr, fieldstr, widget, index); +} /** * Add a UAVObject field to widget relation to the management system * @param object name of the object to add @@ -103,6 +123,28 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel } addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups,instID); } + +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField *field, QWidget *widget, QString element, double scale, bool isLimited, QList *defaultReloadGroups, quint32 instID) +{ + QString objstr; + QString fieldstr; + if(obj) + objstr=obj->getName(); + if(field) + fieldstr=field->getName(); + addUAVObjectToWidgetRelation(objstr, fieldstr, widget, element, scale, isLimited, defaultReloadGroups, instID); +} +void ConfigTaskWidget::addUAVObjectToWidgetRelation(UAVObject * obj,UAVObjectField * field, QWidget * widget, int index,double scale,bool isLimited,QList* defaultReloadGroups, quint32 instID) +{ + QString objstr; + QString fieldstr; + if(obj) + objstr=obj->getName(); + if(field) + fieldstr=field->getName(); + addUAVObjectToWidgetRelation(objstr,fieldstr,widget,index,scale,isLimited,defaultReloadGroups,instID); +} + /** * Add an UAVObject field to widget relation to the management system * @param object name of the object to add diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index f4f0b6b9c..3433a85c1 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -94,11 +94,18 @@ public: static double listMean(QList list); void addUAVObject(QString objectName, QList *reloadGroups=NULL); + void addUAVObject(UAVObject * objectName, QList *reloadGroups=NULL); + void addWidget(QWidget * widget); void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, int index=0, double scale=1, bool isLimited=false, QList *defaultReloadGroups=0, quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field,QWidget * widget,QString element,double scale,bool isLimited=false,QList* defaultReloadGroups=0,quint32 instID=0); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); + void addUAVObjectToWidgetRelation(UAVObject *obj, UAVObjectField * field, QWidget *widget, QString index); //BUTTONS// void addApplySaveButtons(QPushButton * update,QPushButton * save); From 56b094ababa78ae191404f6bef574b92deb62d49 Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 20 Aug 2012 16:10:17 +0100 Subject: [PATCH 099/116] GCS/OPMap - Changed the date of the license header on both the lib and plugin --- .../src/libs/opmapcontrol/src/core/accessmode.h | 2 +- .../libs/opmapcontrol/src/core/alllayersoftype.cpp | 2 +- .../src/libs/opmapcontrol/src/core/alllayersoftype.h | 2 +- .../src/libs/opmapcontrol/src/core/cache.cpp | 2 +- .../src/libs/opmapcontrol/src/core/cache.h | 2 +- .../libs/opmapcontrol/src/core/cacheitemqueue.cpp | 2 +- .../src/libs/opmapcontrol/src/core/cacheitemqueue.h | 2 +- .../src/libs/opmapcontrol/src/core/diagnostics.cpp | 2 +- .../src/libs/opmapcontrol/src/core/diagnostics.h | 2 +- .../libs/opmapcontrol/src/core/geodecoderstatus.h | 2 +- .../libs/opmapcontrol/src/core/kibertilecache.cpp | 2 +- .../src/libs/opmapcontrol/src/core/kibertilecache.h | 2 +- .../src/libs/opmapcontrol/src/core/languagetype.cpp | 2 +- .../src/libs/opmapcontrol/src/core/languagetype.h | 2 +- .../src/libs/opmapcontrol/src/core/maptype.h | 2 +- .../src/libs/opmapcontrol/src/core/memorycache.cpp | 2 +- .../src/libs/opmapcontrol/src/core/memorycache.h | 2 +- .../src/libs/opmapcontrol/src/core/opmaps.cpp | 2 +- .../src/libs/opmapcontrol/src/core/opmaps.h | 2 +- .../src/libs/opmapcontrol/src/core/placemark.cpp | 2 +- .../src/libs/opmapcontrol/src/core/placemark.h | 2 +- .../src/libs/opmapcontrol/src/core/point.cpp | 2 +- .../src/libs/opmapcontrol/src/core/point.h | 2 +- .../libs/opmapcontrol/src/core/providerstrings.cpp | 2 +- .../src/libs/opmapcontrol/src/core/providerstrings.h | 2 +- .../src/libs/opmapcontrol/src/core/pureimage.cpp | 2 +- .../src/libs/opmapcontrol/src/core/pureimage.h | 2 +- .../libs/opmapcontrol/src/core/pureimagecache.cpp | 2 +- .../src/libs/opmapcontrol/src/core/pureimagecache.h | 2 +- .../src/libs/opmapcontrol/src/core/rawtile.cpp | 2 +- .../src/libs/opmapcontrol/src/core/rawtile.h | 2 +- .../src/libs/opmapcontrol/src/core/size.cpp | 2 +- .../src/libs/opmapcontrol/src/core/size.h | 2 +- .../libs/opmapcontrol/src/core/tilecachequeue.cpp | 2 +- .../src/libs/opmapcontrol/src/core/tilecachequeue.h | 2 +- .../src/libs/opmapcontrol/src/core/urlfactory.cpp | 2 +- .../src/libs/opmapcontrol/src/core/urlfactory.h | 2 +- .../src/internals/MouseWheelZoomType.cpp | 2 +- .../opmapcontrol/src/internals/copyrightstrings.h | 12 ++++++------ .../src/libs/opmapcontrol/src/internals/loadtask.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/loadtask.h | 2 +- .../opmapcontrol/src/internals/mousewheelzoomtype.h | 2 +- .../libs/opmapcontrol/src/internals/pointlatlng.cpp | 2 +- .../libs/opmapcontrol/src/internals/pointlatlng.h | 2 +- .../src/internals/projections/lks94projection.cpp | 2 +- .../src/internals/projections/lks94projection.h | 2 +- .../src/internals/projections/mercatorprojection.cpp | 2 +- .../src/internals/projections/mercatorprojection.h | 2 +- .../projections/mercatorprojectionyandex.cpp | 2 +- .../internals/projections/mercatorprojectionyandex.h | 2 +- .../internals/projections/platecarreeprojection.cpp | 2 +- .../internals/projections/platecarreeprojection.h | 2 +- .../projections/platecarreeprojectionpergo.cpp | 2 +- .../projections/platecarreeprojectionpergo.h | 2 +- .../opmapcontrol/src/internals/pureprojection.cpp | 2 +- .../libs/opmapcontrol/src/internals/pureprojection.h | 2 +- .../libs/opmapcontrol/src/internals/rectangle.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/rectangle.h | 2 +- .../libs/opmapcontrol/src/internals/rectlatlng.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/rectlatlng.h | 2 +- .../libs/opmapcontrol/src/internals/sizelatlng.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/sizelatlng.h | 2 +- .../src/libs/opmapcontrol/src/internals/tile.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/tile.h | 2 +- .../libs/opmapcontrol/src/internals/tilematrix.cpp | 2 +- .../src/libs/opmapcontrol/src/internals/tilematrix.h | 2 +- .../opmapcontrol/src/mapwidget/configuration.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/configuration.h | 2 +- .../src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/gpsitem.h | 2 +- .../src/libs/opmapcontrol/src/mapwidget/homeitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/homeitem.h | 2 +- .../libs/opmapcontrol/src/mapwidget/mapripform.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/mapripform.h | 2 +- .../libs/opmapcontrol/src/mapwidget/mapripper.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/mapripper.h | 2 +- .../libs/opmapcontrol/src/mapwidget/opmapwidget.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/opmapwidget.h | 2 +- .../libs/opmapcontrol/src/mapwidget/trailitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/trailitem.h | 2 +- .../opmapcontrol/src/mapwidget/traillineitem.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/traillineitem.h | 2 +- .../src/libs/opmapcontrol/src/mapwidget/uavitem.cpp | 2 +- .../src/libs/opmapcontrol/src/mapwidget/uavitem.h | 2 +- .../opmapcontrol/src/mapwidget/uavmapfollowtype.h | 2 +- .../libs/opmapcontrol/src/mapwidget/uavtrailtype.h | 2 +- .../opmapcontrol/src/mapwidget/waypointcircle.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/waypointcircle.h | 2 +- .../libs/opmapcontrol/src/mapwidget/waypointitem.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/waypointitem.h | 2 +- .../libs/opmapcontrol/src/mapwidget/waypointline.cpp | 2 +- .../libs/opmapcontrol/src/mapwidget/waypointline.h | 2 +- .../src/plugins/opmap/flightdatamodel.cpp | 2 +- .../openpilotgcs/src/plugins/opmap/flightdatamodel.h | 2 +- ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/homeeditor.h | 2 +- .../openpilotgcs/src/plugins/opmap/modelmapproxy.cpp | 2 +- .../openpilotgcs/src/plugins/opmap/modelmapproxy.h | 2 +- .../src/plugins/opmap/modeluavoproxy.cpp | 2 +- .../openpilotgcs/src/plugins/opmap/modeluavoproxy.h | 2 +- .../src/plugins/opmap/opmap_edit_waypoint_dialog.cpp | 2 +- .../src/plugins/opmap/opmap_edit_waypoint_dialog.h | 2 +- .../src/plugins/opmap/opmap_statusbar_widget.cpp | 2 +- .../src/plugins/opmap/opmap_statusbar_widget.h | 2 +- .../src/plugins/opmap/opmap_zoom_slider_widget.cpp | 2 +- .../src/plugins/opmap/opmap_zoom_slider_widget.h | 2 +- .../openpilotgcs/src/plugins/opmap/opmapgadget.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/opmapgadget.h | 2 +- .../src/plugins/opmap/opmapgadgetconfiguration.cpp | 2 +- .../src/plugins/opmap/opmapgadgetconfiguration.h | 2 +- .../src/plugins/opmap/opmapgadgetfactory.cpp | 2 +- .../src/plugins/opmap/opmapgadgetfactory.h | 2 +- .../src/plugins/opmap/opmapgadgetoptionspage.cpp | 2 +- .../src/plugins/opmap/opmapgadgetoptionspage.h | 2 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 2 +- .../src/plugins/opmap/opmapgadgetwidget.h | 2 +- .../openpilotgcs/src/plugins/opmap/opmapplugin.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/opmapplugin.h | 2 +- .../openpilotgcs/src/plugins/opmap/pathplanner.cpp | 2 +- ground/openpilotgcs/src/plugins/opmap/pathplanner.h | 2 +- .../src/plugins/opmap/widgetdelegates.cpp | 2 +- .../openpilotgcs/src/plugins/opmap/widgetdelegates.h | 2 +- 122 files changed, 127 insertions(+), 127 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h index d152936f2..f81efa710 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file accessmode.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.cpp index 4a6e87a88..e1b956f9c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file alllayersoftype.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h index 94f7442b5..3f351e83d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file alllayersoftype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.cpp index eb910b56a..e4059af55 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file cache.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h index 3162de00d..8811d4ae7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file cache.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp index e926ebf6b..1d7d2b1cd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file cacheitemqueue.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h index 45cf8beb5..89676624b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file cacheitemqueue.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp index 33bbbcc58..eb345a2c8 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file diagnostics.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h index 113faef19..07269b5fa 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file diagnostics.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h index 58b653dee..53e4b0c70 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file geodecoderstatus.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.cpp index 37c45f83f..af5ae472d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file kibertilecache.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.h index f856dee8b..d117d0361 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/kibertilecache.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file kibertilecache.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp index 2c4ee2a7c..432719c71 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file languagetype.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h index 4b8411e45..577a0a81a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file languagetype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/maptype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/maptype.h index 741832abc..16ac1a8e1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/maptype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/maptype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file maptype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.cpp index 94df6d0bc..88f7e3a6b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file memorycache.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.h index 88a7e6ec6..237bd3a7e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/memorycache.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file memorycache.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp index b2db6747d..86660fd3e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file OPMaps.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.h index f94f3fa06..81b7daf2c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file OPMaps.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp index 1f8971aae..8bee1b057 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file placemark.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h index 3f338b3f5..3606d9991 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file placemark.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp index a8f43ed0e..145c1b225 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file point.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h index 83d1f079e..5e46ca926 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file point.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp index 8d1f63e30..5fda6ac71 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file providerstrings.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h index 8759057b4..504453fd0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file providerstrings.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp index e938db04d..fe4dabcab 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureimage.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h index 76e1b552f..44e51594b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureimage.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.cpp index be38fcbfa..eb16755ea 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureimagecache.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.h index 7d8942b31..d92d58090 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimagecache.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureimagecache.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp index f357ae50f..12d58e43d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rawtile.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h index 7b3901f6f..1493b2bb5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rawtile.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp index 65a26fac2..7709de7ee 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file size.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h index da340b9a6..0a0a5a7dc 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file size.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.cpp index 166e66a29..9843f2f45 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tilecachequeue.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h index a0bf2b7e0..f53873f3b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tilecachequeue.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.cpp index ca250228b..2ebdeffc5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file urlfactory.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.h index 2f4bfbeb1..a40947cc2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/urlfactory.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file urlfactory.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp index d36691145..3d67f27ec 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file MouseWheelZoomType.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h index 6115297d6..edea169c1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file copyrightstrings.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget @@ -31,11 +31,11 @@ #include namespace internals { -static const QString googleCopyright = QString("©%1 Google - Map data ©%1 Tele Atlas, Imagery ©%1 TerraMetrics").arg(QDate::currentDate().year()); -static const QString openStreetMapCopyright = QString("© OpenStreetMap - Map data ©%1 OpenStreetMap").arg(QDate::currentDate().year()); -static const QString yahooMapCopyright = QString("© Yahoo! Inc. - Map data & Imagery ©%1 NAVTEQ").arg(QDate::currentDate().year()); -static const QString virtualEarthCopyright = QString("©%1 Microsoft Corporation, ©%1 NAVTEQ, ©%1 Image courtesy of NASA").arg(QDate::currentDate().year()); -static const QString arcGisCopyright = QString("©%1 ESRI - Map data ©%1 ArcGIS").arg(QDate::currentDate().year()); +static const QString googleCopyright = QString("%1 Google - Map data %1 Tele Atlas, Imagery %1 TerraMetrics").arg(QDate::currentDate().year()); +static const QString openStreetMapCopyright = QString(" OpenStreetMap - Map data %1 OpenStreetMap").arg(QDate::currentDate().year()); +static const QString yahooMapCopyright = QString(" Yahoo! Inc. - Map data & Imagery %1 NAVTEQ").arg(QDate::currentDate().year()); +static const QString virtualEarthCopyright = QString("%1 Microsoft Corporation, %1 NAVTEQ, %1 Image courtesy of NASA").arg(QDate::currentDate().year()); +static const QString arcGisCopyright = QString("%1 ESRI - Map data %1 ArcGIS").arg(QDate::currentDate().year()); } #endif // COPYRIGHTSTRINGS_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp index 0deb23025..00e373cfb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file loadtask.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h index df38337b0..662420d6e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file loadtask.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h index 218815c36..59938129d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mousewheelzoomtype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.cpp index 850401582..7869a723a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pointlatlng.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.h index 190cabec9..2c30cf6ff 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pointlatlng.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pointlatlng.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp index 13e6f4fb4..82a59ab23 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file lks94projection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h index 4eee20aaa..66581c694 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file lks94projection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp index 30b94d2e4..cd5bbb95b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mercatorprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h index 1c55f5638..25e52df1b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mercatorprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp index 0a695308d..54812e60c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mercatorprojectionyandex.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h index 949f83f1f..af9cc620e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mercatorprojectionyandex.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp index be3989d92..18688ca06 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file platecarreeprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h index c57285a2f..61454f00d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file platecarreeprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp index c9ad01d1f..106674ad2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file platecarreeprojectionpergo.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h index f0ca29fdf..cf52aa036 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file platecarreeprojectionpergo.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index 94c452936..b817ff25e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h index 5b2406225..5402d13e6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pureprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp index f513b2271..ac31898af 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rectangle.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h index 78919c1af..0cc20d1ee 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rectangle.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp index 2d9877262..4cc98f5e3 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rectlatlng.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h index bbc86bac1..8a54cc84b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file rectlatlng.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp index 9222c3704..e22527429 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file sizelatlng.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h index 4ee5388cc..c22249314 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file sizelatlng.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp index 5d8289e71..b70887d7d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tile.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h index 6b1ae2023..5055ca6c6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tile.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp index 658d3be95..9def2e176 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tilematrix.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.h index 0f431567d..dd56e0987 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file tilematrix.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp index 2dd1b95b4..d32b8dcb2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configuration.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A class that centralizes most of the mapcontrol configurations * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h index 46dd0d03c..cadb045ca 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configuration.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A class that centralizes most of the mapcontrol configurations * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index 6c2bee192..07d75da2a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file gpsitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a UAV * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h index 22de85c96..c78c734aa 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file gpsitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 22f5062e3..6dad1e034 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file homeitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a trail point * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index 5d5b6cde3..4830f9b52 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file homeitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp index b2baf5b21..55eadacc2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapripform.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Form to be used with the MapRipper class * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h index 6f150fd4d..d3df3f881 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapripform.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Form to be used with the MapRipper class * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 04f33c20b..4c8bbcd1c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapripper.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A class that allows ripping of a selection of the map * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index 2c426d3d1..a53c443f5 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapripper.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A class that allows ripping of a selection of the map * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index 56084f5c2..30eea862d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapwidget.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief The Map Widget, this is the part exposed to the user * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h index 16e1eb766..020f3831b 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapwidget.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief The Map Widget, this is the part exposed to the user * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp index 0337768ad..fabf6ee9a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file trailitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a trail point * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h index 12cf03c7b..f926d61fc 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file trailitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp index d6353b31b..4550613db 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file trailitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a trail point * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h index 357998153..0243907fa 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file traillineitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp index a06872b0f..506d90b65 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file uavitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a UAV * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h index 2c5657996..472563f37 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file uavitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h index a2321a4c3..5fca96b68 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file uavmapfollowtype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief An enum representing the various map follow modes * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavtrailtype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavtrailtype.h index e9a852960..df8489aa7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavtrailtype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavtrailtype.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file uavtrailtype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief An enum representing the uav trailing modes * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp index 5fc785369..9f045a701 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointcircle.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a circle connecting 2 waypoints * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h index 4be7b0898..db839819d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointcircle.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointcircle.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a circle connecting 2 waypoints * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp index 1582d03ab..e60f749ed 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index 452eef81e..9be8e39cc 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a WayPoint * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp index a31c93cbb..527ca46f9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointline.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a line connecting 2 waypoints * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h index 5b7a40f85..6b6bc4133 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointline.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file waypointline.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief A graphicsItem representing a line connecting 2 waypoints * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp index a1aafb21f..04bcdd93c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file flightdatamodel.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h index f07a79c6e..3043c607c 100644 --- a/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h +++ b/ground/openpilotgcs/src/plugins/opmap/flightdatamodel.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file flightdatamodel.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp index 9c2d9dc9d..47b5466f0 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file homeeditor.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/homeeditor.h b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h index e0214c207..e0404e6b9 100644 --- a/ground/openpilotgcs/src/plugins/opmap/homeeditor.h +++ b/ground/openpilotgcs/src/plugins/opmap/homeeditor.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file homeeditor.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index c76ab9a7f..ba538459e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file modelmapproxy.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h index 12b0654aa..29c61c9b1 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file modelmapproxy.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp index bff405364..d11ee753b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file modeluavproxy.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h index 42d020628..c4a74dcd5 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h +++ b/ground/openpilotgcs/src/plugins/opmap/modeluavoproxy.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file modeluavproxy.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 32ae8887e..6d9f36523 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_edit_waypoint_dialog.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h index 55368fdd6..2219de69e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_edit_waypoint_dialog.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.cpp index 4a8740794..a4135467d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_statusbar_widget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.h b/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.h index ecb2d6206..705961b48 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_statusbar_widget.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_statusbar_widget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.cpp index e73b054ed..dcbdf6a06 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_zoom_slider_widget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.h b/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.h index 83087413e..41b9ff10d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_zoom_slider_widget.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmap_zoom_slider_widget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp index 5ad7cb1db..a0a92cdc8 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h index d83b01782..323e61e5e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadget.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp index 2e1465365..b9dec0c97 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h index 0efb87050..9a8a9bd75 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetconfiguration.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.cpp index 5a3908c89..fb4b73efa 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetfactory.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.h index 4caf96e84..138efcb90 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetfactory.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetfactory.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp index 2136a24d0..92d676e10 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetoptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.h index 1deb13617..85a9433db 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetoptionspage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 25fd84f3b..b5fb5b273 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 65a93e6c0..a1c5bcdd2 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapgadgetwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapplugin.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapplugin.cpp index 5f78b8bf8..1c0f5e057 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapplugin.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapplugin.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapplugin.h b/ground/openpilotgcs/src/plugins/opmap/opmapplugin.h index 93b9351ac..3da9926cf 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapplugin.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapplugin.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file opmapplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp index 95dbcacf6..745be5928 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pathplanner.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h index 5f0bfffee..274e0ae67 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.h +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file pathplanner.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp index 99f21d966..8610322aa 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file widgetdelegates.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h index 684d93ee6..0800d4fef 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file widgetdelegates.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup OPMapPlugin OpenPilot Map Plugin From 0c240cffa5b7c1233ed3a4e5bbcc6722112b259c Mon Sep 17 00:00:00 2001 From: PT_Dreamer Date: Mon, 20 Aug 2012 16:21:12 +0100 Subject: [PATCH 100/116] GCS/OPMap- Change one of the function names to proper camelcase --- .../libs/opmapcontrol/src/internals/core.cpp | 2 +- .../libs/opmapcontrol/src/internals/core.h | 2 +- .../src/mapwidget/mapgraphicitem.cpp | 2 +- .../src/mapwidget/mapgraphicitem.h | 2 +- .../src/plugins/opmap/modelmapproxy.cpp | 26 +++++----- .../opmap/opmap_edit_waypoint_dialog.cpp | 50 +++++++++---------- .../src/plugins/opmap/pathplanner.cpp | 2 +- .../src/plugins/opmap/widgetdelegates.cpp | 18 +++---- .../src/plugins/opmap/widgetdelegates.h | 4 +- 9 files changed, 54 insertions(+), 54 deletions(-) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp index 275f8b965..b484f2537 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file core.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h index 2bb2f3134..dca51d646 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/core.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file core.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index 2eed323ac..587303d6d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapgraphicitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief The main graphicsItem used on the widget, contains the map and map logic * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h index 06786e222..a87450dd1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.h @@ -2,7 +2,7 @@ ****************************************************************************** * * @file mapgraphicitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief The main graphicsItem used on the widget, contains the map and map logic * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget diff --git a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp index ba538459e..406d8e23d 100644 --- a/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/modelmapproxy.cpp @@ -82,18 +82,18 @@ modelMapProxy::overlayType modelMapProxy::overlayTranslate(int type) { switch(type) { - case mapDataDelegate::MODE_FLYENDPOINT: - case mapDataDelegate::MODE_FLYVECTOR: - case mapDataDelegate::MODE_DRIVEENDPOINT: - case mapDataDelegate::MODE_DRIVEVECTOR: + case MapDataDelegate::MODE_FLYENDPOINT: + case MapDataDelegate::MODE_FLYVECTOR: + case MapDataDelegate::MODE_DRIVEENDPOINT: + case MapDataDelegate::MODE_DRIVEVECTOR: return OVERLAY_LINE; break; - case mapDataDelegate::MODE_FLYCIRCLERIGHT: - case mapDataDelegate::MODE_DRIVECIRCLERIGHT: + case MapDataDelegate::MODE_FLYCIRCLERIGHT: + case MapDataDelegate::MODE_DRIVECIRCLERIGHT: return OVERLAY_CIRCLE_RIGHT; break; - case mapDataDelegate::MODE_FLYCIRCLELEFT: - case mapDataDelegate::MODE_DRIVECIRCLELEFT: + case MapDataDelegate::MODE_FLYCIRCLELEFT: + case MapDataDelegate::MODE_DRIVECIRCLELEFT: return OVERLAY_CIRCLE_LEFT; break; default: @@ -167,23 +167,23 @@ void modelMapProxy::refreshOverlays() createOverlay(wp_current,findWayPointNumber(wp_error),wp_error_overlay,Qt::red); switch(model->data(model->index(x,flightDataModel::COMMAND)).toInt()) { - case mapDataDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: + case MapDataDelegate::COMMAND_ONCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::green); break; - case mapDataDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: + case MapDataDelegate::COMMAND_ONCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); break; - case mapDataDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: + case MapDataDelegate::COMMAND_ONNOTCONDITIONJUMPWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::yellow); break; - case mapDataDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: + case MapDataDelegate::COMMAND_ONNOTCONDITIONNEXTWAYPOINT: wp_next=findWayPointNumber(x+1); createOverlay(wp_current,wp_next,wp_next_overlay,Qt::yellow); break; - case mapDataDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: + case MapDataDelegate::COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT: wp_next=findWayPointNumber(wp_jump); createOverlay(wp_current,wp_next,wp_jump_overlay,Qt::green); wp_next=findWayPointNumber(x+1); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 6d9f36523..cab739b8e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -42,12 +42,12 @@ opmap_edit_waypoint_dialog::opmap_edit_waypoint_dialog(QWidget *parent,QAbstract connect(ui->cbCondition,SIGNAL(currentIndexChanged(int)),this,SLOT(setupConditionWidgets())); connect(ui->pushButtonApply,SIGNAL(clicked()),this,SLOT(pushButtonApply_clicked())); connect(ui->pushButtonCancel,SIGNAL(clicked()),this,SLOT(pushButtonCancel_clicked())); - mapDataDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); - mapDataDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); - mapDataDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); + MapDataDelegate::loadComboBox(ui->cbMode,flightDataModel::MODE); + MapDataDelegate::loadComboBox(ui->cbCondition,flightDataModel::CONDITION); + MapDataDelegate::loadComboBox(ui->cbCommand,flightDataModel::COMMAND); mapper = new QDataWidgetMapper(this); - mapper->setItemDelegate(new mapDataDelegate(this)); + mapper->setItemDelegate(new MapDataDelegate(this)); connect(mapper,SIGNAL(currentIndexChanged(int)),this,SLOT(currentIndexChanged(int))); mapper->setModel(model); mapper->setSubmitPolicy(QDataWidgetMapper::ManualSubmit); @@ -101,18 +101,18 @@ void opmap_edit_waypoint_dialog::on_pushButtonOK_clicked() void opmap_edit_waypoint_dialog::setupModeWidgets() { - mapDataDelegate::ModeOptions mode=(mapDataDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); + MapDataDelegate::ModeOptions mode=(MapDataDelegate::ModeOptions)ui->cbMode->itemData(ui->cbMode->currentIndex()).toInt(); switch(mode) { - case mapDataDelegate::MODE_FLYENDPOINT: - case mapDataDelegate::MODE_FLYVECTOR: - case mapDataDelegate::MODE_FLYCIRCLERIGHT: - case mapDataDelegate::MODE_FLYCIRCLELEFT: - case mapDataDelegate::MODE_DRIVEENDPOINT: - case mapDataDelegate::MODE_DRIVEVECTOR: - case mapDataDelegate::MODE_DRIVECIRCLELEFT: - case mapDataDelegate::MODE_DRIVECIRCLERIGHT: - case mapDataDelegate::MODE_DISARMALARM: + case MapDataDelegate::MODE_FLYENDPOINT: + case MapDataDelegate::MODE_FLYVECTOR: + case MapDataDelegate::MODE_FLYCIRCLERIGHT: + case MapDataDelegate::MODE_FLYCIRCLELEFT: + case MapDataDelegate::MODE_DRIVEENDPOINT: + case MapDataDelegate::MODE_DRIVEVECTOR: + case MapDataDelegate::MODE_DRIVECIRCLELEFT: + case MapDataDelegate::MODE_DRIVECIRCLERIGHT: + case MapDataDelegate::MODE_DISARMALARM: ui->modeParam1->setVisible(false); ui->modeParam2->setVisible(false); ui->modeParam3->setVisible(false); @@ -122,7 +122,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(false); ui->dsb_modeParam4->setVisible(false); break; - case mapDataDelegate::MODE_FIXEDATTITUDE: + case MapDataDelegate::MODE_FIXEDATTITUDE: ui->modeParam1->setText("pitch"); ui->modeParam2->setText("roll"); ui->modeParam3->setText("yaw"); @@ -136,7 +136,7 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() ui->dsb_modeParam3->setVisible(true); ui->dsb_modeParam4->setVisible(true); break; - case mapDataDelegate::MODE_SETACCESSORY: + case MapDataDelegate::MODE_SETACCESSORY: ui->modeParam1->setText("Acc.channel"); ui->modeParam2->setText("Value"); ui->modeParam1->setVisible(true); @@ -152,12 +152,12 @@ void opmap_edit_waypoint_dialog::setupModeWidgets() } void opmap_edit_waypoint_dialog::setupConditionWidgets() { - mapDataDelegate::EndConditionOptions mode=(mapDataDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); + MapDataDelegate::EndConditionOptions mode=(MapDataDelegate::EndConditionOptions)ui->cbCondition->itemData(ui->cbCondition->currentIndex()).toInt(); switch(mode) { - case mapDataDelegate::ENDCONDITION_NONE: - case mapDataDelegate::ENDCONDITION_IMMEDIATE: - case mapDataDelegate::ENDCONDITION_PYTHONSCRIPT: + case MapDataDelegate::ENDCONDITION_NONE: + case MapDataDelegate::ENDCONDITION_IMMEDIATE: + case MapDataDelegate::ENDCONDITION_PYTHONSCRIPT: ui->condParam1->setVisible(false); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -167,7 +167,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam3->setVisible(false); ui->dsb_condParam4->setVisible(false); break; - case mapDataDelegate::ENDCONDITION_TIMEOUT: + case MapDataDelegate::ENDCONDITION_TIMEOUT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -178,7 +178,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Timeout(ms)"); break; - case mapDataDelegate::ENDCONDITION_DISTANCETOTARGET: + case MapDataDelegate::ENDCONDITION_DISTANCETOTARGET: ui->condParam1->setVisible(true); ui->condParam2->setVisible(true); ui->condParam3->setVisible(false); @@ -190,7 +190,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->condParam1->setText("Distance(m)"); ui->condParam2->setText("Flag(0=2D,1=3D)");//FIXME break; - case mapDataDelegate::ENDCONDITION_LEGREMAINING: + case MapDataDelegate::ENDCONDITION_LEGREMAINING: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -201,7 +201,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); break; - case mapDataDelegate::ENDCONDITION_ABOVEALTITUDE: + case MapDataDelegate::ENDCONDITION_ABOVEALTITUDE: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); @@ -212,7 +212,7 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Altitude in meters (negative)"); break; - case mapDataDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: + case MapDataDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); ui->condParam3->setVisible(false); diff --git a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp index 745be5928..aed5eed6e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/pathplanner.cpp @@ -50,7 +50,7 @@ void pathPlanner::setModel(flightDataModel *model,QItemSelectionModel *selection ui->tableView->setModel(model); ui->tableView->setSelectionModel(selection); ui->tableView->setSelectionBehavior(QAbstractItemView::SelectRows); - ui->tableView->setItemDelegate(new mapDataDelegate(this)); + ui->tableView->setItemDelegate(new MapDataDelegate(this)); connect(model,SIGNAL(rowsInserted(const QModelIndex&,int,int)),this,SLOT(rowsInserted(const QModelIndex&,int,int))); wid=new opmap_edit_waypoint_dialog(NULL,model,selection); ui->tableView->resizeColumnsToContents(); diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp index 8610322aa..7bd385842 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -28,7 +28,7 @@ #include #include #include -QWidget *mapDataDelegate::createEditor(QWidget *parent, +QWidget *MapDataDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem & option, const QModelIndex & index) const { @@ -38,18 +38,18 @@ QWidget *mapDataDelegate::createEditor(QWidget *parent, { case flightDataModel::MODE: box=new QComboBox(parent); - mapDataDelegate::loadComboBox(box,flightDataModel::MODE); + MapDataDelegate::loadComboBox(box,flightDataModel::MODE); return box; break; case flightDataModel::CONDITION: box=new QComboBox(parent); - mapDataDelegate::loadComboBox(box,flightDataModel::CONDITION); + MapDataDelegate::loadComboBox(box,flightDataModel::CONDITION); return box; break; case flightDataModel::COMMAND: box=new QComboBox(parent); - mapDataDelegate::loadComboBox(box,flightDataModel::COMMAND); + MapDataDelegate::loadComboBox(box,flightDataModel::COMMAND); return box; break; default: @@ -61,7 +61,7 @@ QWidget *mapDataDelegate::createEditor(QWidget *parent, return editor; } -void mapDataDelegate::setEditorData(QWidget *editor, +void MapDataDelegate::setEditorData(QWidget *editor, const QModelIndex &index) const { if(!index.isValid()) @@ -78,7 +78,7 @@ void mapDataDelegate::setEditorData(QWidget *editor, QItemDelegate::setEditorData(editor, index); } -void mapDataDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, +void MapDataDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const { QString className=editor->metaObject()->className(); @@ -91,13 +91,13 @@ void mapDataDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, QItemDelegate::setModelData(editor,model,index); } -void mapDataDelegate::updateEditorGeometry(QWidget *editor, +void MapDataDelegate::updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &/* index */) const { editor->setGeometry(option.rect); } -void mapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDataEnum type) +void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDataEnum type) { switch(type) { @@ -138,6 +138,6 @@ void mapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa } } -mapDataDelegate::mapDataDelegate(QObject *parent):QItemDelegate(parent) +MapDataDelegate::MapDataDelegate(QObject *parent):QItemDelegate(parent) { } diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h index 0800d4fef..ae29bc975 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h @@ -32,7 +32,7 @@ #include "flightdatamodel.h" -class mapDataDelegate : public QItemDelegate +class MapDataDelegate : public QItemDelegate { Q_OBJECT @@ -47,7 +47,7 @@ class mapDataDelegate : public QItemDelegate COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; - mapDataDelegate(QObject *parent = 0); + MapDataDelegate(QObject *parent = 0); QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const; From d8ea84cdf1470d9222ef4470d0639d01d6674011 Mon Sep 17 00:00:00 2001 From: a*morale Date: Tue, 21 Aug 2012 00:50:09 +0200 Subject: [PATCH 101/116] Fix output power selection from the configured value at startup --- flight/PipXtreme/System/pios_board.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/PipXtreme/System/pios_board.c b/flight/PipXtreme/System/pios_board.c index 3a2dd0544..b32582c90 100644 --- a/flight/PipXtreme/System/pios_board.c +++ b/flight/PipXtreme/System/pios_board.c @@ -346,7 +346,7 @@ void PIOS_Board_Init(void) { pios_rfm22b_cfg.maxRFBandwidth = 128000; break; } - switch (pipxSettings.RFSpeed) + switch (pipxSettings.MaxRFPower) { case PIPXSETTINGS_MAXRFPOWER_125: pios_rfm22b_cfg.maxTxPower = RFM22_tx_pwr_txpow_0; From ffd52200712b086b738133a12e51daa6a8051622 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Tue, 21 Aug 2012 22:09:53 +0300 Subject: [PATCH 102/116] CameraStab UI: some reformatting and comments --- .../config/configcamerastabilizationwidget.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 9c4470a1d..55c170fd2 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -151,11 +151,13 @@ void ConfigCameraStabilizationWidget::refreshWidgetsValues(UAVObject *obj) */ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() { - // Save state of the module enable checkbox first - HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); - quint8 value = m_camerastabilization->enableCameraStabilization->isChecked() ? + // Save state of the module enable checkbox first. + // Do not use setData() member on whole object, if possible, since it triggers + // unnessesary UAVObect update. + quint8 enableModule = m_camerastabilization->enableCameraStabilization->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; - hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB,value); + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + hwSettings->setOptionalModules(HwSettings::OPTIONALMODULES_CAMERASTAB, enableModule); // Update mixer channels which were mapped to camera outputs in case they are // not used for other function yet @@ -218,6 +220,8 @@ void ConfigCameraStabilizationWidget::updateObjectsFromWidgets() } } while(widgetUpdated); + // FIXME: Should not use setData() to prevent double updates. + // It should be refactored after the reformatting of MixerSettings UAVObject. mixerSettings->setData(mixerSettingsData); ConfigTaskWidget::updateObjectsFromWidgets(); From 8d5c1e4253088ee7f616a8e5811f72ec47365967 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Wed, 22 Aug 2012 04:49:26 +1000 Subject: [PATCH 103/116] Change Default GPS protocol to UBX --- shared/uavobjectdefinition/gpssettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/gpssettings.xml b/shared/uavobjectdefinition/gpssettings.xml index 5c38f43fe..af58793d1 100644 --- a/shared/uavobjectdefinition/gpssettings.xml +++ b/shared/uavobjectdefinition/gpssettings.xml @@ -1,7 +1,7 @@ Settings for the GPS - + From 2f168323d2d7e34c36bd588c69516e176bc1b594 Mon Sep 17 00:00:00 2001 From: David Ankers Date: Fri, 17 Aug 2012 23:02:31 +1000 Subject: [PATCH 104/116] Default to telem on main port, no reasons against this unless I am being stupid (very possible). --- shared/uavobjectdefinition/hwsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 00c904dd4..308cf01ac 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -2,7 +2,7 @@ Selection of optional hardware configurations. - + From b946d8162aae442be2047fb1505d9d7603e92de9 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 23 Aug 2012 13:39:37 +0300 Subject: [PATCH 105/116] CameraStab UI: add comment about reference implementation --- .../plugins/config/configcamerastabilizationwidget.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index 55c170fd2..ae5712f5e 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -24,6 +24,15 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + +/* + * IMPORTANT: This module is meant to be a reference implementation which + * demostrates the use of ConfigTaskWidget API for widgets which are not directly + * related to UAVObjects. It contains a lot of comments including some commented + * out code samples. Please DO NOT COPY/PASTE them into any other module based + * on this. + */ + #include "configcamerastabilizationwidget.h" #include "camerastabsettings.h" #include "hwsettings.h" From 81ddbda972b2ed8915dcc726fa0ba871016c01ea Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 25 Aug 2012 17:12:37 -0500 Subject: [PATCH 106/116] Sensors: Scope some variables to suppress warnings --- flight/Modules/Sensors/sensors.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 22d22b250..01cdee594 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -226,8 +226,6 @@ static void SensorsTask(void *parameters) AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); } - int32_t read_good; - int32_t count; for (int i = 0; i < 3; i++) { accel_accum[i] = 0; @@ -245,6 +243,9 @@ static void SensorsTask(void *parameters) { struct pios_bma180_data accel; + int32_t read_good; + int32_t count; + count = 0; while((read_good = PIOS_BMA180_ReadFifo(&accel)) != 0 && !error) error = ((xTaskGetTickCount() - lastSysTime) > SENSOR_PERIOD) ? true : error; From d4794d139fa3f92ca226db51446abba22bee6600 Mon Sep 17 00:00:00 2001 From: Stacey Sheldon Date: Sat, 25 Aug 2012 23:46:40 -0400 Subject: [PATCH 107/116] gcs: fix pipx-related typos in GCS This also fixes the auto-selecting of FW images for pipx in the uploader GUI by making the board name match fw_pipxtreme. --- ground/openpilotgcs/src/plugins/config/pipxtreme.ui | 2 +- .../src/plugins/uavobjectutil/devicedescriptorstruct.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui index 9de1a7120..89616441b 100644 --- a/ground/openpilotgcs/src/plugins/config/pipxtreme.ui +++ b/ground/openpilotgcs/src/plugins/config/pipxtreme.ui @@ -1612,7 +1612,7 @@ - AES Encription + AES Encryption diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h index a725c0bfe..b83a76a15 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/devicedescriptorstruct.h @@ -20,7 +20,7 @@ public: return QString("OpenPilot INS"); break; case 0x0301://PipX - return QString("PipXtreame"); + return QString("PipXtreme"); break; case 0x0401://Coptercontrol return QString("CopterControl"); From 882f23b344fe048fc1fca2c490385691c646187c Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:04:40 -0500 Subject: [PATCH 108/116] AndroidGCS: Clean up some warnings from OsgViewer --- .../org/openpilot/androidgcs/OsgViewer.java | 58 ++----------------- 1 file changed, 4 insertions(+), 54 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java index 9928b19cf..be4d507c2 100644 --- a/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java +++ b/androidgcs/src/org/openpilot/androidgcs/OsgViewer.java @@ -10,11 +10,9 @@ import android.graphics.Color; import android.graphics.PointF; import android.os.Bundle; import android.os.Environment; +import android.util.FloatMath; import android.util.Log; import android.view.KeyEvent; -import android.view.Menu; -import android.view.MenuInflater; -import android.view.MenuItem; import android.view.MotionEvent; import android.view.View; import android.view.View.OnClickListener; @@ -79,12 +77,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList uiLightChangeButton = (Button) findViewById(R.id.uiButtonLight); uiLightChangeButton.setOnClickListener(uiListenerChangeLight); - //Creating Toasts - msgUiNavPrincipal = Toast.makeText(getApplicationContext(), "toast1", Toast.LENGTH_SHORT); - msgUiNavSecondary = Toast.makeText(getApplicationContext(), "toast2", Toast.LENGTH_SHORT); - msgUiLightOn = Toast.makeText(getApplicationContext(), "toast3", Toast.LENGTH_SHORT); - msgUiLightOff = Toast.makeText(getApplicationContext(), "toast4", Toast.LENGTH_SHORT); - String address = Environment.getExternalStorageDirectory().getPath() + "/Models/J14-QT_X.3DS"; //quad.osg"; Log.d(TAG, "Address: " + address); osgNativeLib.loadObject(address); @@ -135,7 +127,6 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList //dumpEvent(event); - long time_arrival = event.getEventTime(); int n_points = event.getPointerCount(); int action = event.getAction() & MotionEvent.ACTION_MASK; @@ -204,6 +195,8 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList else osgNativeLib.mouseButtonReleaseEvent(event.getX(0), event.getY(0), 1); break; + default: + break; } mode = moveTypes.ZOOM; distanceOrigin = sqrDistance(event); @@ -299,53 +292,10 @@ public class OsgViewer extends ObjectManagerActivity implements View.OnTouchList osgNativeLib.setClearColor(red,green,blue); } - //Android Life Cycle Menu - @Override - public boolean onCreateOptionsMenu(Menu menu) { - MenuInflater inflater = getMenuInflater(); -// inflater.inflate(R.menu.appmenu, menu); - return super.onCreateOptionsMenu(menu); - } - @Override - public boolean onOptionsItemSelected(MenuItem item) { - // Handle item selection - switch (item.getItemId()) { - default: - return super.onOptionsItemSelected(item); - } - } - - //Utilities - /** Show an event in the LogCat view, for debugging */ - private void dumpEvent(MotionEvent event) { - String names[] = { "DOWN", "UP", "MOVE", "CANCEL", "OUTSIDE", - "POINTER_DOWN", "POINTER_UP", "7?", "8?", "9?" }; - StringBuilder sb = new StringBuilder(); - int action = event.getAction(); - int actionCode = action & MotionEvent.ACTION_MASK; - sb.append("event ACTION_").append(names[actionCode]); - if (actionCode == MotionEvent.ACTION_POINTER_DOWN - || actionCode == MotionEvent.ACTION_POINTER_UP) { - sb.append("(pid ").append( - action >> MotionEvent.ACTION_POINTER_ID_SHIFT); - sb.append(")"); - } - sb.append("["); - for (int i = 0; i < event.getPointerCount(); i++) { - sb.append("#").append(i); - sb.append("(pid ").append(event.getPointerId(i)); - sb.append(")=").append((int) event.getX(i)); - sb.append(",").append((int) event.getY(i)); - if (i + 1 < event.getPointerCount()) - sb.append(";"); - } - sb.append("]"); - //Log.d(TAG, sb.toString()); - } private float sqrDistance(MotionEvent event) { float x = event.getX(0) - event.getX(1); float y = event.getY(0) - event.getY(1); - return (float)(Math.sqrt(x * x + y * y)); + return (float)(FloatMath.sqrt(x * x + y * y)); } // The below methods should all be called by the parent activity at the appropriate times From 89997de1cc02ed9256af482e45573f4366a888ff Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:05:53 -0500 Subject: [PATCH 109/116] AndroidGCS: Suppress some warnings from Controller.java --- androidgcs/src/org/openpilot/androidgcs/Controller.java | 1 - 1 file changed, 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/Controller.java b/androidgcs/src/org/openpilot/androidgcs/Controller.java index 0d3a3c911..39a86639c 100644 --- a/androidgcs/src/org/openpilot/androidgcs/Controller.java +++ b/androidgcs/src/org/openpilot/androidgcs/Controller.java @@ -70,7 +70,6 @@ public class Controller extends ObjectManagerActivity { public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.controller); - TextView manualView = (TextView) findViewById(R.id.manualControlValues); } Observer settingsUpdated = new Observer() { From c2e55ecc21c49b10486b3c53b09e0cb8e77395a0 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 26 Aug 2012 22:26:34 -0500 Subject: [PATCH 110/116] AndroidGCS: Suppress some warnings related to not implementing the STRING uavfield type properly. --- .../openpilot/androidgcs/ObjectEditView.java | 26 ++++++++++++------- .../org/openpilot/uavtalk/UAVObjectField.java | 25 +++++++++++------- 2 files changed, 32 insertions(+), 19 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java index 7946a357b..401a26978 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectEditView.java @@ -22,22 +22,22 @@ public class ObjectEditView extends GridLayout { public List fields; public ObjectEditView(Context context) { - super(context); + super(context); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { + public ObjectEditView(Context context, AttributeSet ats, int defaultStyle) { super(context, ats); initObjectEditView(); } - public ObjectEditView(Context context, AttributeSet ats) { + public ObjectEditView(Context context, AttributeSet ats) { super(context, ats); initObjectEditView(); } public void initObjectEditView() { - // Set orientation of layout to vertical + // Set orientation of layout to vertical setOrientation(LinearLayout.VERTICAL); setColumnCount(2); fields = new ArrayList(); @@ -51,11 +51,11 @@ public class ObjectEditView extends GridLayout { for (int i = 0; i < field.getNumElements(); i++) addRow(getContext(), field, i); } - - + + public void addRow(Context context, UAVObjectField field, int idx) { int row = getRowCount(); - + TextView fieldName = new TextView(context); if(field.getNumElements() == 1) { fieldName.setText(field.getName()); @@ -65,7 +65,7 @@ public class ObjectEditView extends GridLayout { addView(fieldName, new GridLayout.LayoutParams(spec(row), spec(0))); View fieldValue = null; - switch(field.getType()) + switch(field.getType()) { case FLOAT32: fieldValue = new EditText(context); @@ -93,8 +93,16 @@ public class ObjectEditView extends GridLayout { ((Spinner) fieldValue).setAdapter(adapter); ((Spinner) fieldValue).setSelection((int) field.getDouble(idx)); break; + case BITFIELD: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); + ((EditText)fieldValue).setInputType(InputType.TYPE_CLASS_NUMBER); + break; + case STRING: + fieldValue = new EditText(context); + ((EditText)fieldValue).setText(field.getValue(idx).toString()); } - + addView(fieldValue, new GridLayout.LayoutParams(spec(row), spec(1))); fields.add(fieldValue); } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java index d07fdf6fd..7fea950f0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectField.java @@ -578,6 +578,12 @@ public class UAVObjectField { ((ArrayList) data).add((byte) 0); } break; + case STRING: + ((ArrayList) data).clear(); + for(int index = 0; index < numElements; ++index) { + ((ArrayList) data).add((byte) 0); + } + break; } } @@ -633,7 +639,7 @@ public class UAVObjectField { numBytesPerElement = 1; break; case STRING: - data = new ArrayList(this.numElements); + data = new ArrayList(this.numElements); numBytesPerElement = 1; break; default: @@ -650,15 +656,9 @@ public class UAVObjectField { */ protected Long bound (Object val) { - switch(type) { - case ENUM: - case STRING: - return 0L; - case FLOAT32: - return ((Number) val).longValue(); - } - - long num = ((Number) val).longValue(); + long num = 0; + if (isNumeric()) + num = ((Number) val).longValue(); switch(type) { case INT8: @@ -703,6 +703,11 @@ public class UAVObjectField { if(num > 255) return (long) 255; return num; + case FLOAT32: + return ((Number) val).longValue(); + case ENUM: + case STRING: + return 0L; } return num; From e6ccfb9c610db12c14cf47fcc169e5cfc14754ad Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 09:53:23 -0500 Subject: [PATCH 111/116] AndroidGCS: Make sure the telemetry sevice checks there is a telemetry task AND it's connected before sending the OPConnected service. Otherwise the objMngr is undefined. --- .../org/openpilot/androidgcs/telemetry/OPTelemetryService.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java index 4698900ef..88cb9a632 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java @@ -258,7 +258,7 @@ public class OPTelemetryService extends Service { mServiceHandler.sendMessage(msg); } public boolean isConnected() { - return activeTelem != null; + return (activeTelem != null) && (telemTask != null) && (telemTask.getConnected()); } }; From 57cf7c67a63982d3f50012fe64215ed5953dfff7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Mon, 27 Aug 2012 11:05:08 -0500 Subject: [PATCH 112/116] AndroidGCS PFD: Properly center image now so it works over multiple sizes. However, it doesn't automatically fill the screen in normal PFD view yet. Specifying the width in pfd.xml directly does fix that but is incorrect. --- .../openpilot/androidgcs/AttitudeView.java | 26 ++++++++++++------- .../org/openpilot/androidgcs/PfdActivity.java | 5 ++-- 2 files changed, 19 insertions(+), 12 deletions(-) diff --git a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java index d8aecc5e1..3bf0e5227 100644 --- a/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java +++ b/androidgcs/src/org/openpilot/androidgcs/AttitudeView.java @@ -93,25 +93,33 @@ public class AttitudeView extends View { @Override protected void onDraw(Canvas canvas) { - final int PX = getMeasuredWidth() / 2; - final int PY = getMeasuredHeight() / 2; + final int PX = getMeasuredWidth(); + final int PY = getMeasuredHeight(); - // TODO: Figure out why these magic numbers are needed to center it - final int WIDTH = 600; - final int HEIGHT = 600; - final int DEG_TO_PX = 10; // Magic number for how to scale pitch + // Want 60 deg to move the horizon all the way off the screen + final int DEG_TO_PX = (PY/2) / 60; // Magic number for how to scale pitch - canvas.save(0); - canvas.rotate(-roll, PX, PY); + canvas.save(); + canvas.rotate(-roll, PX / 2, PY / 2); canvas.translate(0, pitch * DEG_TO_PX); Drawable horizon = getContext().getResources().getDrawable( R.drawable.im_pfd_horizon); + // This puts the image at the center of the PFD canvas (after it was // translated) - horizon.setBounds(-(WIDTH - PX) / 2, -(HEIGHT - PY) / 2, WIDTH, HEIGHT); + double margin = 0.5; + horizon.setBounds( (int) (-margin * PX), (int) (-margin * PY), (int) ((1 + margin) * PX), (int) ((1+margin) *PY)); horizon.draw(canvas); canvas.restore(); + canvas.drawLine(0, 0, PX, 0, markerPaint); + canvas.drawLine(0, 0, 0, PY, markerPaint); + canvas.drawLine(PX, 0, PX, PY, markerPaint); + canvas.drawLine(0, PY, PX, PY, markerPaint); + + canvas.drawLine(0,PY/2,PX,PY/2,markerPaint); + canvas.drawLine(PX/2,0,PX/2,PY,markerPaint); + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java index 6374c7b82..8b74fe928 100644 --- a/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/PfdActivity.java @@ -28,7 +28,6 @@ import org.openpilot.androidgcs.fragments.PFD; import android.app.FragmentTransaction; import android.os.Bundle; import android.view.View; -import android.widget.AbsListView; import android.widget.LinearLayout; public class PfdActivity extends ObjectManagerActivity { @@ -44,8 +43,8 @@ public class PfdActivity extends ObjectManagerActivity { layout.setOrientation(LinearLayout.HORIZONTAL); layout.setLayoutParams(new LinearLayout.LayoutParams( - AbsListView.LayoutParams.MATCH_PARENT, - AbsListView.LayoutParams.MATCH_PARENT)); + LinearLayout.LayoutParams.WRAP_CONTENT, + LinearLayout.LayoutParams.WRAP_CONTENT)); layout.setId(0x101); { FragmentTransaction fragmentTransaction = getFragmentManager() From 3e6f98b2e89a60f7ca9c0c423f3f56e1413bbc27 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 28 Aug 2012 18:32:49 -0500 Subject: [PATCH 113/116] Update the OSX packaged icons to those from 3rdeyepro / dacat. --- ground/openpilotgcs/src/app/openpilotgcs.icns | Bin 36754 -> 128653 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ground/openpilotgcs/src/app/openpilotgcs.icns b/ground/openpilotgcs/src/app/openpilotgcs.icns index 8785d587fcc6e821856076d05af0e2609c4ef48a..a7966a9609d1100202e64e5f7cdd70d2f4ffee2c 100644 GIT binary patch literal 128653 zcmeFa2Xs}()h~XV8o1yXJGMdX_TGC_qlhZ1KoU)WDW>-h=iJ`Z3o7(35KTf7RnqNO z;FdV~BlZ}yRvE?BvaME+;V z(go`nBoZn2!T;h1L>a3B5>pF4v5 zTR3{YclYj*qs`5?ZZ_Y|zm4keVOx&ezJ2R9kmciu{_d8ew*)ug`Tm_d1pm>yHw6O0 zE&Tp%{KsBt_wL++B9PeoeE)7fe(&}zfuR5SwgA6>zxnQ+<{$49ANLKE$6ky3pGiyCDdZ#)0F6OI(Ez9!1dVP<|S;gSR@j1rXHL<&T_Wrjk!#LfY0YKoo_8nPL~vHS8#Y-E{DUM z+hj^-(36L!bJ;8wlgUWoGt<-4(o$1dOgix;IVCxH`0!!F8GMZn*WwzQN~KYq@20sLz@*aZ#aOb)v&C<*-cyl_NI$UiP|AmPw_`ngvpgT0X@+ z@51#CTqERdStnE~6zZu{x_V;K(~J1{YMxvslL}?yw;m0>dVT+yWgLkF6A$7|KRkD$ z?fi}36ti$qijeJodr=xgRbA@(bMT{HjBw% z(CJtjIW-kap|bgUgH0c&)oQeAHszK1bFn$r*>OchvlfiX!Jwsy8AcOybjFAb%sd$S z+i04ZtF(YPJs@Kd2oPrM58})jPTBXs-w}%_gp$^yP6c<@nsO3j5X!8!B4p)uc z*J*J&j{C$CdF4E@QYk9Fvi@xJ!mj=fm#P;{y&4IJPA=r_TEUS@Bx0Uq?B>J%p6H%a zOE{S5DIs+Df!X8nGqKm_GKE4+z+gFlyD)_=E!eK)@p;hY%(*8_bS6C|na<@9J)SCH zV(D1gvn&>a=n&O;YV|tpie+frYuY=n{q*T<6aW3+=aZU$e|%8? zzxlc0A$kAZbK^tw4?pjDsDAH5?WtE^_<4I<#ba_N!aPb&e28yAA9oF?w*ORy^ej;@(2Uyv=DjnUjW$PBK`OZ!J9xQ)o z#e@&6wEgwXN1%S|y?o%klizRq{o8`O{p;{O#DDJ=GCaS}a#&^mRo{#OJD5&1Ex*@0 zKj%j_HY3w}DQ@2byYA-;?!sc*|G5XA>mwlCbN``wWHDN*`(@m@cS`_^b3Z%!7cJf3 zxn2_V|A*`G+h7`=-%s)%^~eFh)4NOf5B~f2py*cb4gg4C9|5cVPx|3IF1RVU-M<4s zyNLVuiG4;D@8Ka%=( zRzLaS-@g1vTDlzVgOV7O2iw=<>#S?-YaFZMwskF?mOBQ^#YWpk*+ya`5^{2~CoUeH znPtheXW+0Cuo=mwY-^^KcyJmi22+*|)=msINO5|NL1Qr53>0GqQRFZt7|b;%cVub| zRy`D&Tt?iGq@EuO#g0r=>h+k8qSc$MMymnWCo0@ge<0evK#prDYOTp;uA6vl~ZcD+M;?|F}|>%V5X+BCvtRWZD76#m&eJtmgsmf zuB0jyawAsoM85fK&>!w@*kKULWSBILw>>slq{J1NoHn_rKsV9ij|*R`9M2a)9p4q3 zBve}E@ltdCG~w!))jv4W<;vlS#Jq~=L_Q|RWrYhc z9nwUJL^;iVE*uTw{=`7Eb*14{XdKrn#b6JWB;v7U`M&mOB!KzjgW(Rpe+(Ow;9{$2 z5NAngzFfDk?rJm)bpgLWmn{)nL>O#3p5^Yj5oyUx<7BQr3V3VR;|-%^#-*6*2DQjqt@s!y;MCt6pXFQc86cB&yj01a9Gi2 z=jCWsnsLkKnYCJ-d|OYbYrI@O`}7;Z{V=CHOmu+O8 zB^Vd&s-7qmW3mLk`}$-NjBiYtppcH=u|=}>x;6Mj%L*=gYL_QWO%ta412B$Y^2)158Ro-iIv3iY(DHl2=4;KS&#NC(4Ko6nKY zD81Md3t_>8aO_erIG!)Zq`1T)9>iT*K0|3-+|bz*#e(snU~n8)DzS-i(NO-r*J2m4 znf#o!M}pTQ!BAHwS1fjlp5>dagu)k8d;ym!7`O9uoWSKsSF}ZQ=oU7{!kJVS z9QH6CnajmE@o=6=RWB3aP>wNZbUFi-+JKHsPsN#J1_Ps8(@9(_lvscQqg!A+#HXgF zu{o@tm0+pXltc~>9TMSiWCt2N)s{j_W0T|=I6CW?NJbQy5Re8mA~vqVR@zp$mswt+ zZrHzY3O*W#)xZYl#CSL-j$bf}2ymMjhglytP>tCc5bsuaw7~3-;@m=fkB0?84Y6v~ zla0iJUcnKfu34e6I5!g zPCI(`7`04O;N5IiqBSAnzlzp`ldqnhDp9I&t!ze3_k0@e%AQgHl$WOdZq{Y1FamBSUnvJjcTlUpF-rDE+Ufh7_NSh@%M zBbT=6*qr+Cc&LNvKS?YUE2i4ch9UvHJINnuS!p~O9LJMdVPO~y&;pk&o$hUmg#B1| zLLk)M-945o#USP_!a;1bHt1ijyAlaOrN6s-3|k@+Ifc*i8n1`XXVJM?s}FWZgWdkC zX12%jA1w|TCxIn?r6rV|PJ}QOrhPh&mJA%ioW@8|E*0Pq z>UcUOEiD}fZk!p%V5BG0A^NRpwA3_af9&JwHdr0-6fzU=0dj9WmWriVljDXbvw2Lq zE!_eHw%)~pmWsxM#Y8rm%3)_CVJ;_*&a}k1U7c4R`RUx6`0!czp@Y}rhn^pPtbMrP zq34H><_}dr_&;6$-`V&7dj0N)9sbbs|Lyg4583IV<=V!C zrR&jA$?zcwJ{XBI-Huy!9@%kl+rh15tIJBF?($VsddezG_m%ASRePx=rCv8iirZ0I zy>@z@XHrR?XJW$y>v()z#dzyD``DzsjI%)v)ka=h8@ti6EGW|)Dj5?0ePQQp_W=EI*?qgzPqw%{fRh zIfIal1nh+}*bozCR)W3UbO@aa`_*ISQqyrG)nG7X*ZrLFn9*(kvPx9e%UEVQX7n1! z#%v#9ATp)gbktaZiX2e%FRDt|3PU0O6J4390(LEB#!7&9F*tE%{;TCR#yFiCR(^vM zYVCTffu`3RGW!}@Z%i`C1RO5l>0%8As_c3jh#(s>O9<`zjDux7#R7MA`L-gRNaZ8y zJ*eJAIQ@|EX_K0laUc?nM53Yd_$Z0a4*WJlIoJn>0_34%#(20hkV^K#aV{Yky}Z+? zG7vO1dMX$K?m1?37^ph#yokde7mS{qDuXRgwce&9>&+hUoyR~ks<{Xx9}PYZ@zI#sE@1h(W<9o$wNGgg6{DBS#z&rgjW94&Y0eNboB zkhPhIpbmg=xWi!K(Gou`(l%QL2MsUOyHWjK!jpCbRVF?jD)rMs{>=)t8){3?aXfQ3 zuv@`MtDY*z?Fy9nX@N+US#AM>QjJv&0xAdvR)bql)v{JcEB$fNQ2)LWt6p`$9<-l)e<2?T>KKQ+=?B=*1_4O3z&s#>jq zXtM!f4fusBQJeuM#)Z1iwTHq^XmR&OxdI(fEK0IUWm8jBY6w`=wTPUoMVnCGGW7OgUp`Zf}&yflv>@#stU{eDhzyNAve{Uo2+cZ=aYa4Xspn$(nqEgB<%UU8% z@J`c25mJL%U{#UTMvTxzf&DCUyIVuk%7ll*(1_4!y$VyusidRIgCPi*@a4r474YG} zhbt)xCG4tEi0cg%dMh|cDOI3;Dbd8KHG&b>0xsz7Qkfdu5GR+vd@dTWgLi{grOXbh zZ3>douBWLL8lAzVcj^)~auJ^|l`4SWs-~*guSDH`O5_y@uEbR|Sx!kHWcSAfqI3OgncW7K{nnup9j({0~Yvbf9t2#lYlFN(F z5Qap~&lJjigqT5wQF)^cGNDkS)HroX8iiQE7a7LSEW!$D;{X7HNTF$jnl|WITIe{O zSuJ2eyh^bysbtVNS=N-o zLQ4U)Xy!OW8ERr-*bU>wDIq+Xpj67FbDE<88;bEVy#!O(i;4=T zPsmb>1tOV3BIF6xx%owfjsi;2B$W$#C0?mi$(eTKweWli4l->Dn%HFT4%A6$B%knAKv*sSrd$;L=Dr za(bLhQrHv$3n9R#h;2lZVQk=9i-xAw=FTj{3K9#8ie^q33oZ2(kTQ@A5l^Tff|NVX z<0pp?mMh}qA_LwPhK7dQ^27>R~tz!Qh`Ew#z9BEs7YGcFfGeih}2i3g{SqPG`U$ zh;;cza-~Xza8U%sc7qfHevh0gQd>g69jTXES1=O*1tmAY3QBaN$gU`tQ>9`jR8j+7!+2XVm9^GU6{A%}}mA9|`)qCP-ZJau6UnO9;3&QV0TMS~M-A@ora8%OS4G+L>@^6fA~j*?(9s*rayybl&m7(oV>$R{NuYbcCe1kaUh zfmK8is}*%}igZko4Tg+S3QQdH)xZJ7bYY#6Ew%x~;Q$^d@X!L6v-lzln5NtffQd}1 zody#Z4ilFWmr>|*B8OqYj-FmD=7=Q{pP0g|B!=kaEFmVwL}anDQtpr?DNSRh6%-W~ zPDIMYY1ZgbA{NVyD#RnqxDsgcCq%l-N3nTgkxd*Y5($K- z`gyEEvPgx?tDw*A5(*d(BT=y6dhjGb{V3v@0WV1l z9~_DX&$$a#3_2HuMiQUPt(~xwG9uTanxv^$SuSLR34)~VnyRC)KW5A z%jH@5U?fwVho6RKH3Hvx8OO?{@*wDujXseJxGa2{fTg(zi(Y&%5^gKgaxu6Gf>FjxWHW^0wx0|}gXMloFfZNCCP{3B1}hi^qeK9SNiIGmeL~RZC+D)t z;R=Auq)Vr}05A^tU~_s($YNVrR0O8F`V2$YYHmP0DJh#{(4x?33D?VWaFaL;hH75b zC1?|DPhzW6?JP1|f}qx3U6{bbckrkj_MtE`&&zc1+~6v>dSj+BP0RK|s5-zurz8xV zWnoib_lx`hZNtI&ZoZF4Wx$X|tP2?!!RlrwGSWCBHy?+Q34=G(nV05ZlUd?^eQtgw zkCM6=90;po7Rv$JN&$*}ikY4&m}ET{j)cRp_L%_1;w&nY$pU>i{Ppl_c~owC73!_f zF#*w^rEE8A5M-&zi+qO<>@cQbER1PkP>6gd4}TAj%2c$0(`hkFI)_uj_OfiKRdg;p z70_XvVWpE9LO1^)kCHYc?1k^K&G?uiJTODLf!X*i(?gWH%g5adL3RXi8C%*~ExrHNOxM1yb=2(~GhcCe^l zUJ0TrA?T26;~A;yZI`34sfLXl1L59?u!Qaa>)?iyE^rd6OV}>BFip#FcST?hjjc{$ z0UZW3c2Mq2Ckb$ZtQ1-YR?_L?YJ+g&O9_rm#XuM$@_{gs3xVs1$jN>JG6~a|`G+E* z;5lKs7g|t8FNOOeN@|+O0*&wim5Z<&V>f@@=73#4mxLwzhEs z;yVv*b8l_lT(OCaBfxc=yR_8e+v~0L>~UARtWK)i<02qeU&Wf~lkmx|N!5AP6L(K2 z8}A(VMBXbtw}Ujx;hU9{Gs2!zk!{byGrd_AkkR5a+cNBCGF-NslT5~GF4y!O-kDkU z5mh-g*;QFJnH3rF#>rOarbSuUPi1u(G{Zb!@#u=2+U&}#+RS=D9w|9X#+3B&)PqFK zM9CPH?fhAZ!$i&)Y59r8ZuUaKh+Zv-qXIpagTNXP=rGqpW`Va)yxm+6SF4`Hg+fMjCZ1!>VvNIfnwRHFJa5Z++&LZw`L zA?ybBh+D6A8g?Vl)=hY)0z~s?MtnhP?C=-`X4s3W?7&wKZlS{Vu%{$Qi*?MC>-NC~ zcqYM93+Wd$qe9jcDGkyh!L2F{!G#e#ZUa>`)*mVh(n7JCOyzF4m51cCo6a9p-2QeA{47K z$*myHgXml!Zl9j2VQ+^n7#s@Dl4~_e{qhU3kRuq^b1DzOUJro>D8kW`tG)d!jj02CyJx)OhqyLOKncv;~HuEi1AmDujblmE77Gcr?^C zK?QD#Qz;jmMOM&a7YfB{i~zL(cg28r>ML_bsSv~nvH*vE#()4&o_OS9%;|7iUp7MC z8FV&Ptm}X-qDGo@Y6pVHWZ9lz6a+^6>t#wWfZ#^Eez-Pwt#ik+{4BXZh;nftn@6h< z^Lfh2Yi&+DZlgM};;b?Rg3pRV8+%+b3$!Oeqfsg5osNZUsLLvhau+~nfL=TF09Y2{ zZl`t2;wdJnKqLqJlP56E+2(ZEZB)B^nWj_+_@@*3E4ol-RYOD7vP@?H?4tIZ7%Q`= zZ3von>4$1YuXfn&PN!w#g7JDtUC&*LJMAtT#W_cf>Bwr0O$X`bQrYPUG%<8#v=aF_ zPAQ*t5?Mu!wM~<{kR-RBrqvf=4$PJW2}s!5;&pbX-D@L{g$xd=L;zPZ2r%bQfU6BK z=@3MSS51?dt^O!TiFQnuIaMUJPfye2u5}=P*g=ZV_Jn<_5fVK#yu#&jv6?{KH=#E5 zV6qCZLRxSl7P5jB%^3;{z+ohnPamh#7-r*+Drmt{6{Z1%v*fkIMPdntx<(`8A3*+% z%$E7U12m~&S9jDJr1g}@lmue#(Ay!N)nnEnXt;ioP>O4)!py7C z0yv~(DIIFBDo!EIKN<^JV4N06?0|OTaHT-g80K0Wz|4Vj*XcJYD8Rh@Bfm=$a!q$lN3ZSWBTrR}{$4h8=dFEy=!Xjv1ULISJz|Dcp1R z6)AUeZ4h-?xW%MI*9>I}ieOa_2#D272mv-?R-q`0oh7zJyK9q4B^=QODw86yV{`a| zSqCFTd#hy#x2%L*7^--bAJVsAGSLFa2jDIU@M)mw${cH{E#9$7tKuw-d4fsN$eyWe z>Ee^I2vGN|0)Pi#F1Rvl3&V5hau$HQ1VU|7L#C;61?Z1=E>I}h?jB$8$ylHwm!)3U z8ViT~6Qv~zFL27w5uBa55`q&=Tuu!|F%f(h@0bYacT=P!_(Uky>BwN3cU`)1S|fKM zG+3-|2S&J88Y6*(9V*P0#N=gFQ?#2MUR#2Fmq{ti>4a4TGS)6_)i6huJ0w;`EdbG` ztEj1=u3WJd;m8;$bgL=yLZ=&?<#4W2D%ta6m1rq#St;dc_R6WkobG-WTt<~jWzaq7 za>KmK?nE85$xB!T3n5X}+8%s|BOT{P7k-4}o-offaB|M3FCc0*`aPDnqA~ zh)zUc>4`*7EtK%fsdE(Y05DsscBm+d(MXG9ycA+fklh)oLmY<-gaVhm zL`GrHBckux$X*V&+NYu@Vf@1I-DQNk6$-mJ)(H84;krB?T#xu<2zF&IfpDRQ`kAaS z45&)!RHq$6eiblLg-OvF@5A12* zpyEh?h3O`AT?M=naX5gZ1ny-rHrruZgNAJ*&{WpE*kRO5XO~F00I|^|5>^%Ai>p~e zf)7P^1w{8CnP$xV%{EvtmceZVwBFux6#4MjYyr=K5H5?D!r4bSzK>N^2^Tgn=}6SM zb2mBj#b|^Gk426L<6!_y;qnQHlnU@M3|p9yGYNevpQ212FOy1CaM6Z1vaf}jz=y$# zTsGeYkfr!Ekkdj}GK7F@0nq6HAQq+%8RS?}g$rH_p9CMoI_+kbz#*mz6m5`h3Boga zQBhpc2v};oWVEw28U?xFu1j0gETK(Ij^ z%Ye8IokY4vIz( z&?f>lH53@j^#b@eh|g!UCrp&qsTr(d!or)18O`BU`Zeb5-0#quH=3s_nMZouFYAk|J-d&S7H5LAbI)uCz!REwJL{GKhS7eH-{2;~arnE0fHUR6%VC1W+7TH2-9b*x^rO5bPMsjR;DJ z9&q#GxeVE=)}AnIt-~EE=3x*}is}(0?ju|m&!%g4T*uX03wiQ>HzRe zlWi?dxArOU^<$E#_5hp8g!gcfV2t4f6cW%%oZv$~Lxny9brhiP>@5NVeDq30XzeRQ zDodcql15G!^phdZ%5)bhI`os~s`L_6&S8HWko3<~|0-tOaNo zH1GcjW@BfMi;cx{500jcG4|nXJGLF#bZ}$!`igbr9X7z(Hrm`CtEsW(o7Lg4S}+oAgVVQSs&ArqLhbmnagAf$W1h^-9lzLRgXBi5s~`)K8}Tf6W=%%D zxe?$UE95llC)?~Nw>tAPEjd`Wj{u|U5&q^iCh78aIoB=7%*oC!A+V@=068j*G~I0H zoRQw2O6nkeanWc8fx97!26%ObV#?0MepcduG{c-~K%E+p=tfBTBALqJv6sFAo;-a| zjmBC)AMBZRK#FA5!+{;ODd0hw?%tN}hWtI*UU*#~E)co2(*((Z)u`4A%=KVC z4k!s?=`vugotsx>x1%K=By zo)5TzH|W%>s&yVMNmmJM6$m<-5%hM`{NaPS@)BLSmaH@Tpr#hUA}$sw>86D*%#mpw zx*AmDfSNses$6<3SlS&Q?Aok^7n^F~rxQ@r8Z$;zLKd5FY^T2riLA9k4*(KX#q~x!-4uTy;DUy< z%#x_QYA3=n>h%raADT|8JOgft3wE7t3x=HCv|tw`657-yfK=3g2rqzf{3(8ScVggl zk$L2z{lTE4JI)`jFv`@GKvM=Z6rBg+CHjTXAJSfcboiVR6**OPTblT=bgId})~GvUaqepfdoTmlGB zoLsT+Y}jvyZVXsekOJt0Y)8mErNHZrWzgJ29pv5dxk{PLO?aKE;w+1}fqALa4nRn@ z*B`Wl^^rX}kOk4p8gCvU~>$FX6uR*1ytz^Tt@0MX-!Cs|K+w6&kbav*&V4znWN1?U56 z@R&yF0$Va&-63d4uydVM?nQF!x+m2WD%+2FmX1~O`H)43YX_<2&>Br~bxTJp))Lp+ zadK0Rs!UDc7KNZu5j&t#knks$%|03S+aLf!r3R@By~(MBF^OqkRB4x;y4-PYzjZ#e zQ6N=9>-ZzqA8K!JwY5-NFFO@ploY05+mVk#^QBgmLrIgEZCzj)HGFK0!~%E`05(qT za~j3C^7acCI@-@PY%j_XbKor7+;PFxLg`o|!_;IYB*}q?)e_msAoAA5k@6B{oLpLX z99c#UpPwpmAxUoSGb-K6Q|&D+t?O>sK-MG z6y;!!5$g>ZCP@pzXKxFs{GA=_K zsDTR^a);6jXKV4aLt#G-uJPxK>@o`ADUjYL*R4O(UIy(rlPkwmLm=PP-|Y`~dPni$ zjbP!TFjx_;ms#MDO_Ph%c+djRbrL&5Rmvg7QZ~7+y|jheR*y2=DC~t{ynB#8dXq$pKNL(+l$|!))IMf~$Rc<_b!Pk=1dU8XCLMas=hvAhJ z2sba4aPq3UQMU!p>LEcAlb6XT{FM>l5APP)5b}ZnBtnsH?I>wUZ0*=%RtR#gg1)3+ z=ak~AOIqUF_G%RD`C(6YQYhFk zg)M&hcsK}@krhIDoh%OCGgGw&;Mv~+xqL`(1wg12SxGyvc5IUX3={EnKN;>S%VjE8 zp9=^4o#VyTGMkhtmYpH^uJqzQ0E0S}6iFetE55A|UdlWcEa`s2AHHJCU>LWz$4;rF zWiq#vDk9X;{E&VpwLtD5#Ip}Zq-I~6w6Wm2jT z-aAogyW<0qv&*F%l^xFgRDRC2UKS$9P^zv~ zQsvnvTbAI)+wBnJO=d`-12`?**c}%N)J)(CFlm*9!dwht z5%0g8Ef9-{oHn%;;+-lN&Ic|^dpXLwld^1)z1?vzGDdKORT8S0xel19zyzsFWU;yu z#V8<$68(`2HW-krg}@{d9trIO$>B@8jBHT}0->0@2)0X^1c;&bL2x-`6ye58z|=ZP z1Wde)EB*t(6lqb@o;{rfO%!JHXPzQXF3kOcX08fb%=j?6mXv1LoIjn{BHVSiY z_;7auME_z5Wb0YsWm^iXf*5m1AHXp19xx`amJO0A@k{S-Pp zO8~FvdPNk@9>VFDGJ3I(I!HkSlt-wZylGGS5^x&eVuypr!HL0!$y}}n4%z%8Ff?J- z?aiW7RLNY@c)*2JlT0Y@PMCGs-vr+4E*s4TOv3`_Uh&C)VbSKc>NT_>UmZ~YLzxXf|#2i)y^qxgT@^}@pH{S?`RNKkU*Oj2q{7tA+iFJ z>$p7AqTQFEU57zTC=`SVua}4{lvRV;8gMoMHiDeh`>#cU{!>4zE(29naQ=s%9Kg2$ zWW*Ma-Eyou5@^s1NwR)C4FTCgZViUIO{3`aEyx!2MGW&5{z7bq$?8KhgekHzBIdX(Ow7} zR$bT%`^Iqayl;+<%eM&a0VrU)7>E14ssB@h0@*9=mGDMGYN=}L#R%*yDdAek zaYJYpLVbw*HVZ*!1u`p<;pXZLTe@k{RjIvLODWxf;3AB-8${W_SR%b`Y)t@OTBrEO zr0pgoq2x9}HBi{uc4!X9N`lljc*8$%R>Y_vC{UIcphsnd6hwnV2PH64cneP5C{HV4 z5>QQfx&slp`vf_F$O~_rr${%=Np*r4A0$-yfP!cJnJR$p=xLDPMATNI+I}-|Ry`Ak z;_~#}sMrR!A(4IPRayGpG)g*;=%0SLtSo&W;7W1uQ%?Z;Mfq#UQAogED7FJw1upn^ zT2Bfk6=7AqguVP_DU{?CPOpzk35n(KB0M>TQ`2W9Qc{-UMnz@+R#cu$;&}Rfu@9kM z*(Jrp{I(b518W1(!cK9Q){ zJ1ilUfzU9Ng4SygD)tPszLW$%JcfY7n9LeR6(rk{)4+qaR8k6_>P<;XO{X(Zz8Qnn z#;X94-@WKh!SM0Od#UXHO}blFxpz ze83794w$B2Rv`<|U-rvDm0AZ%(IfOc*8d2{3{df7{|}I(AED;4{~zI)0V;m% z{{eFJBh)06F>* zY99Ol5sn$4V%q@ed6b&R`XA+)fhm9N|AF!IqqO`_```X3!v?7QvHk&a^dr{{T7q5o#X${}GNEpyJ2= zA0S6RLd|3UKf*BsRO}caJ&#iJSpTCuGce_k{XZ~%ew3ES{(qEb2B!S6{|Cm;kJ9qk z|Bv#_z?47s|G@b9QCggjsu-a1|7rdI)BFGb>H9C+|M2^#tELQ4p#8F%d&&DsV9+Ws?wGLfBpV!3;eVwP`-45R7)bg zf-HIBl}Tx7PY!Ypg6~5Yt>3cxmDTbz_)hBkHxK?@0*}uxU9xa3iG;Y}FD)T~c#r?- z1*?{?CBBh{Kn;Dt!j~73Xz&eDQTwS$6!?z>&+q|p3m)V>m`sA-G5(V{^p*JZiSK`; zC6LKK{dq8j^aNCp$#FCqiTq#|>DjbNGiT20|1)#aq?r#ElAa-v#}zLtUbsQDQ6-j( zWe>_psA;67M&PM>!=IS18gb7!Hrw*8xn58;S0!1`p!}Do_~?p@S(6%mzo~;)=j&=J z`@_A|W8W6P6#rR#UlCN;JDLhzY=xwne`JnxHLJ^OP$O-{Sq^-58D;EfN*T^X_S zjqU?a|Ccm>Tg&b6%I$RCa{GrJS!rJnt;}Ft`}lIs? zYpZTMnLaJl(eOKWIWYx)>+^6PuQ`261IyYqgN`SB;Ns_&cqUo+qGsVBdczv_j$ zuiwkrPJZFb)_=0{XpMD#nRjX^ zFDO@az5VTXs|(fA-!@H7*}DIW(=#_7+qm)V9Shpt-f-;``kP&sN^kZEe*44r%oj&| z^C@37Ecv5_vDZ)gZ|oSeb@=m(LV?$Qq!m|TdBML9a(mRLgdmW`&b{%lRrKXsq0&s-li$NsM6x0Nfu{rL79jYHphBgeB3 zn=7r!Gc;u|2G4r_ca(3^KYfb3DDH`E`zO;Vn?`Tiw7zjocE!mxZyosi8y_SL;Tua{ z-oJm7{SVJuKEFBt`z_khjPE}_%Kz?-@~1{64Egn&p3k;)O?iWxbm*n=-W>D0vZJqI zUyuCb%G4ul^1ZiT`05}Ih z%S*;TP``6$#VYrYvSlY`#>$G1KY#Ptq~9LTRZMby{>k5lD7F^YJ$rP~kU#uxU3hb7 z=&stA(q4#8-gdJ+G~%!4cbwbgeB;;`l^%Cux>xw}lohk(D}Qya{;T8{O5Y<>x5jbv zg;>|kw>QtK`f(ZMjam1KczCewD%oD`TKvTi-zOK=?R|Sbb?>%!{Xa0Xeh_8esU^X$ z4RP$O%szVL@7u2a*Z#QQKRb5pUn{1{2k$xGHMnu;GhdgxpPV;IU!K#F@!EcK{myA+ zZ~bQVf}yjTiF_YS{Xx*xxqOI)6BS z;oUKJ+S4wsVMxBunYYKe#`M(D`8Q@aT=j8ZnEZ$Cu21JRF5dJ&nKQ>H`?e(cR^vCO zjds&Zzn(lY{{7;Qhf$xuw-_JJUiHb6&sEDtf4_6;;LdYp-z(cTS@QPrwr_js^_7F( z+5VevGY*d~efQnlBaYm%9{R+awtmdC?Hdzjd)EE&x7I*m}u#?YqBJnn#6Ox=9l_ADnDTKK{e^)0cYA|L*klwvT1};cJ)P{c4hTg?h^D zjo2sutX`9M@w>+3TcX>Jf41m!ig@j|p<~T~Wv?yj`r@;*FS5HM(W3Py56Ql|D%)^B z`}V6v?XjZCPaa=+opMFNdgAp{-jp1+bB0~s`ug+-gPAMUhJU=u^F0Q4f~+(cO5(TbxF#P*CzhccjvVy%g%SM-lOGJ zm8CtI!wrr9IOm@q)~@M(ZTOfS>+08zExNb=L`rziku$+VM?boe{nZcTjpxj?1M|Kg zxiIJZmGAxj-3#a6`n+OZ%bAzoZn&1Q!BZGwow@jI(^i)0$-*-Wme{<%+9dt;mxB3K z!7VTU{=fcmyE$Q7a>|P*KA_OeHP#jDo=VYVFl4-*DZ=G{`{F~1VdlCY2mRrtly4|Q zJuf};*PCBn`|_`)dD91PGo^jC`sRnJLq&}Tp2sg-@AfkE>471%Ei=x)^pvRU%{pIm z;+VoW?$r+Y2IH+39<<#WlsHsB=$p;iPhP0t-Ti#R8!f|MwdV^iz4@(*{n5T3J?>>I zUj6O9N!u3LuhxuJnqM`p7&+6EfBvnr$FbtX{8xEL%QoNH-Of=hIkjo@Q{`FD*x#CX za?OLe-+yyzYApVRXpmYz`fAtCWq)6M$bSE&eBnC7inMI^6#C$c?d=7UGYg+B+g~(f zmhA1$KkZ!3^xfA_k~U9!YwVYfkqdvE?0e#SZugGG+2fzZzKK=6S&+Um?W^GQD?0|w zSTgSI;Zr|3|J^^{X_zOkD?8Am(;s9t z9)IFJ|FUDFKKbVEwbw3hE6M%#LGc`+{`@MpC`ZsC&)c~+^GNygPX+Tn`;;TQ&~yLK zc9Lz_Co$v18|zB{Ev-M?PbEJ!=jic+XJ))Fs!jc3{FM#%Q1gVY8(**Z^5qrp zJxCg2xZyJIax|)vwxynppQyaGDZjn><57RU@b0f#MMG#)W%ED%^vgFsoPF-b)n#X& ze}?hi7t^oR&3^B~4~3D;8^dlsE2t>mS#{v;6`BJ-ZruFjEm8Q_GtI}|$=#gv9QNkA z&C5$(Q%#bcpk&iV8_3_|Gm}>31>gS5VmEDN!XNHQu1S34uPmxjJSPH|^m+jHY( z)qmuzTs?U0^)L24cgeZp%$P5=A0<7d_$bRk>oQb!sP7ybdr>;~ZuxQ9{^un3!npW@ z8;rr#zPVqYSZQxde(>U~smDr4&z&tgcB%ZgqqhEigI`R2Z8mqcQupz_h3^a!Fm8P7 ze_HXYv%_cHn8dg=r=9ur)h|0nw$Bkazmn;oNB%a`Bur@h^y;LdLCc<-zdvQk;Zv>R z4X>YO{(k^bK(4>#@&$W!4xI)`uEA+$@>Bw~lzm6zxRD50RFrsOxcGYWS;x2PLGbFh zA+1_F+=8%=0s7bB*;*q~0te05$?#j5m#;8zi+5CyHsj;;hEa%wB_?qe=xo4FaLkb|wUGb57xa1SsP!K0G(_sNCx9c+P-Q(NzlT?S($>|D}bgFi! z*&74G+oF?h=j~Mu411icWku8c;x0l2y^-ITpdcqGPEN?Fp@U29Neijh6~XmcuzgxD z1M0hg#opU5;!}YFGEb_!URuX@I{m>jVl_-1fkf&}o6PfI$DSVT7hhC>h#f#!up{$# zY*n4?Vl_$#PC|0%BLt*FNqbAcH&kADk`{_)=|%6Iqsd-WK&1A4K4dPf$Ej_zZAfs0kADY`t*c)LLNxJsz2 z*4+S%r}JUAUL@O>EFrNjhq)=@LOav>v-rAc-7{|}*j4jaJ+-ge+$};EdX|WVG}Wy) zL_O9coPTaMQgH{8%;OKTjQFjRtzZg9=8Q`V#G&I5+$+YOPF;{22|z5urCSY~)6YgC z@KRUTSoq)IdhlFbO#rV*$FNMHXdE1t1{L61TfV=Q|2O%CX8p7K(6en)MIB>Ctw6ay z{p|@kK&ILZTpp8jsPNzU>(<$qvDBu0xEdJtj*iVQoBjw#nz_PApxMJ~$#7AW$7OoWR%U%i46=nw9!v0r_k8rSG~Ui z{x_BNGQ5@Tk4!&LL|Wk6C4q3t?oy-T2?#2wTpe90u`6NytG@noCcHv?R)37sD0BG77d(jU_&IC{C5AUP49JT+)Y>iE;!6rm9lL|f_< zC81f~JqM<$hjKtNcYMz0{|BD?Bak4%}_qF%dVV2wnt zjJHU892*FH|0&PfAGhCP3eL8o!9#geO-8A(}^Yi1BATp)!H6_jEyC+m1fGjBqhmOX?#3`*X=I2 ztZ|gF>L%R2=Qh9>*k!dq*jL4+jaoj^-+rS7(sOzdQm^;tuv`|SjsgpweXICthJ~38 z;wBV(odDPTdsw-dpH5fITdPCX8G1YMEq!odFSyg(IJYL3Ski4~c6gj`ZsR!~d+97; zM52_vyAUzH`t2^{Jtbenmt10#@}byUT?Qxgmewigs^nHSxJ}k(Mk$^KaU=@1^F@ z6XD$K(q}8<-kz2YFsK6WMB#4H$8W(V7fer9BwoFBzQD?g37Ns}xZ7QNNRHQIMwmFn zA3KFIN8J^1M@XcQDhG`eji;Ri3qVov`J;sE&SjU@$3S3i*mjq(ukUFBF!<8?05QQF zGNxzhmex*F?5+WUeA}T?w`!y}_vY@g4Y-ED|7yuN=zD~51pv*7?xiT!Ov5BQbKP(& zhV;LK7XAW@(E7@n?_tcXh&G7+;>(X}Yf`pcb{vuoHOHAm9#B<2F@)F-ZgxCfTxm}LD@`@vV>@I{=?p1$sG zETA`aK$W8ibcbtwC(h&D1Z+qmg-a6xtb1N2*YqZ&753SBs!!&|G|5rn-5q3CTPDTn zZ(tPZDv|jnSs(&9T4;YsA=;4g4$8vtfn3Fi&3AReqEx~P?htfeApdxpQey7tjKvX0 zmN)`{2eSnTt1w2{wsoUe0e8Q(g4MDPyWv>a7Veh!n+3m%Fi3r*$I#sS2&u`xiq?S_aj7;!m zuY@0bC}BOau!5P5!4+qK`NqNkl0fCrDzUw4BP8P&L&@G!Li8Rr=u8c3z;Di1+^C#M zjAzyzp|boKvtl8jFkT^K%#W`jFldHZ5SX)PwWZDB$ zVOJa0kOVG}v(Ikc%0dTDVYw<08}PCB9cwqT#=MPc;MOxq(d;fJ`xm?{17c>+Kz)95 zv%PG#r`#w1eGj4UN8rO!pC%{+-mPEE&^}d7wQJ`}gq&dOx^Hj5(0Ji_)uT+K0Hp&= z{I^LH@RXKp$_Gs!&NbLS@<&Fln1Lsi^{(e-8foDi-NQK<3SHw{?!ASUo4)5FaTimy zx${NTrU93f<_t@&raZ#@+Sdz%)8S`>^0$vtD~tN+tZcF)WRK}@72n`Z09*|#JO6{I z>u?<(OuHPeT0fM^2Pp+OGw;vIT9^pPb!C!bXOhZmd^bRDy~^4-A+u2gp%o%8^XiQA zRO;6S6jG*R9iqjZ%F}IG3s1FtcH=7J316BDr~iM$u-hvqk(}`3%$-MIByW3ctG=5y zJnH)z8P(e}BG!h(0zvjN&}>Tj!c2OkiE;1f&Cd|c4Dk>@yV@?hZfTmDjTo?uBqEhE zCXrR>@AELMro*RhP2+%%AcJ)Gn1DwH2NVB#lL!AqXLpMH#iP%kkRNXf7`_T~$0%jM z5r>~5@OshD>Gl_Fp(T=DevmD@)w#(m7~@@&fm)Zf)PqqV{}d81vx3chVDzp&bwa*4 zl~xo6OQxK_f0TZDEb1h8EH&?d#K3_+0b@>p?1zb_4{W-73w0F zOXy8W?8vX)r z-%66}qVE&S8inN4*oouG=(#(&GX03I?WKWdRV?Zl%+pOiR*hmPU$5w+o=pADYbvjc z09=50{;YICu|_TCOD&^+yHhvOflPUWY5c52^v_Ab!x!fmMw0}@#h#!0(`h$S3Q=CE zo;U)LruxUnQI}P&Ko0v~qa*c?oIEB*KV-(;k8O5SKd+6ZtYVnvWCO#sU9w$WmIOE% zSD`QR7m=Q;<+boRJ36b;pD~Y(QEbxlE5A&PAi^&tAp~)z>G!_Bv*Fw?$5lA z&l-5=Ottc*u*}}tj4+rL=YmR^yQN8-VmF5l@#+^8E9j+H~TJKX$x_U(m0eAxq$1TG}40T_QERPacGVLx$Q)Lr0E& zhQuQhYZ$8}`!~x%l!&)2Gbxr6ua8rQMajA*kYg9PeJHf^-eD0Sc2IcMyH<>A)^x+p z7ok;ntrbvtBP#XODX`oj}!H?%g`hS-$7{)~#i= zfs_F$abW@!X8FDGSb5f>Z%p1)K=+OYJf0qvfI}UZue#EWE%A+KP^j^!SDuGGL>LzW zfJpj0)H|U#LH8a+9JvzCkh@2Gv&Z$tH-WDpM4e9|%Df?hh15k|R1dtv)%mecDk{ug zY3rtuuA$0d`Yg8a&nG_w9f>0dpqe@UBG;x6v@_j+ARhrgB9x#MaX)sbKT8!byF9yC zq`b2xtfS0IQWLR~!Rw4suxyZ>F zkaqzVfdfdA+(aQ4@l7d>Tkz>>;7EU~lxMFy`VvNZKaTE_p*K{E$qOUnT{Z@#vLTHk zI2`wcaQ;}P4hjns@a6^z2d7jbod@{%pxoHoLi?bUnG@dPRJ+X;?zv>vCB8FXYzs!= zh|8AC700xD$iN11&uN3==4U2!iVI|BXG2}qzZRhT@7(vCtqn<$`xpNgr#J*;Zbfwg zyr%Aoo6~G>DdZiENJy8`6>6EX_ci9Oiksfx>IUtdW^*?pH4+EX86D988wP3L=hojx z3y~<8lpEW$3+#l?E3tpX{0C=$1seI-M=GhlnOe+;xYBmu`DcOr@2lryFUF?phq^CHR3Sg&8>>e0N}$HXj|M^W(n1uTUuAfibYs2Ka9XNRcSygl zwAgyNJfa->%LS}tj2=L8%@OLAZM+t;y^uJX&QV%co?$zt^7i1+9i%v;(1N}J zFsmB(GXxN7#IlM{FR^p88 zak|f_cQ_w!w2mJhY+3gD_Vna@^z!}tdV|h$6^oL=7Yd}lpANC_6JZRuyg-ZOnHfy+ z=~YlE4`1r*n8O)SN3OAO=k9(~cEP{cdCsu8h)%K}%B1X*Y6==a5kIJaF4#7r$Kb`o zdj(0{H*%$ztMLN?Q0)G408aciYSd@BC>rF2WJ15m@6eoCcf2n{>N-FMiBCUQ3TN&` z4}@$9L4w6p$!f6-Q6*AgG#H|PAPoCb1qCqvORy&%Oq1_K-XP%yIvlBjF*FIkY5|&*Kd*jey1}e)8a9C$IlP+ zo)MgNT3*d_vxH)(7T*rb!)Sd5&4y6By2~&Vhc-qx*^h+PQwNDtIW1EP&?ZbW97^kO zWkv|q%#>M}@U@NhOGh*AH|KcFQQ=SZN-~y7=JjS@kihx-;{)gQQv>JpWa%dH>64Dh ztI|5qg>FWisEOFkaq*n=<&#t_jtp z>hMTAis+zZR^1rr+2MsES6ePc@Y}H@t5zvr+4f>~ZNXIncQ*l;K9tZJq_##)N&e9k z9j<1zcqceByD_C^_No($3C2*L-KN~V1!V{)u=@5SK=^WkHEkk_7}Z^n3o%OBx>+51 zNrZSR+wjELiXBuIRTrC@xKk>5(5G7y#5)~jcaK%r!{_P9S^c|?%G9|iJ5Emf$NWBk zelwp$#3oA6e}vWJV@GB!(=krOj^xDm7fcD~hBCIfzO>;5P4#FeBc-yGd;Dob)-E}* zk^z5H$PN>D)=`uZ0OKYii=%WEgbj`RNmd?LtLsE^2E&;eGBoPB_%$pNhD2A2i^M4o z9>kMKY6Wd(tf?Wd{8?tHVWe8x)M*K%A(72oaL&7&3!Ad_=1(o`Wvp6Ad;Q9SxU9=8aH#I)>j;xi3r82bjLLL=>{x0Xrqwnivxl-i{%QR zz7rnES=NFn39Aq=bS+h@Kd;ICxEkc#1V45fHTa0z`#tr*kXE(f;NsCyDxcwM(^PZn zAK1&vBQha?FJ40S%I%qvD7;G`rM^mw5gleg6w0T6y7G3q0Zbhz6`^^X@{^-0p&GEz z?3Uw`65MLfW@iX^lQ&7HoxGTck^?13rQXi4srIqA3u zlKscVwG+7@JC$~(M+8H$D*r>ib>aBAx`nv@oxt5g$Ge*YKM?O_R8a=tXFJlnU%q

dV8G=n1sbCUzrkv9jakhs7!rY2IE3yRmn`ql| zO%hIM_qT%WACM}_1)`BMb!tq9t#3d$YrB@gk-;PKOt~kK>0olpV6kFwioEQKfJmCnkpb_KTtbbZM=H@2kztI}ViV?Yb{qZL z6PdXYSltyde_!peg=oycwWvjO>fa}*c&}I#QjTW}(38g|t>ISYrM8w4{Vt@)^J@?vkL@6$1 z2mA*Zs;}tXco|s*5cD!4GZHp5%ZYu{ty*>{8V{wb-LYW+i zxN6*#qL(KP#qk){YNGbO3mkQ$VE|VIQAxZ`8?VpsnM@=7*=~1rS7u|NK<%71NmBOq zDAJF>znr}`YD~rl>q2kIvw5In^&;Fb{QlTfW1`ZDHCZ;KKCyeS)eg*zlI>_c6@}J8 z$k}gORJxfs-$(%-R8`dtW($5DK<*UAbi;OYy9Zu{PpJVMuZYn$TjDpGR$`D1{n->A zR(H@4?~)Q)+wLwk0RprIOLDH)0(8`wFC~yjvL0uQDCa-PNlcdnH&onaR@s1`G}7_Y zq&F;NDlX-d-uYyuh*r7;rXn*1+=iBKd26(-k1U1~W$?|16H8=RGd5pzWuq&Tu=szp zh5WSiw*m-co}C51I0C##qv@vaULjTWeMA69a3LPR5qwu6VW;e{mkD*!MGMb`24z$j z@x2q%BQ92xF-8Dlej=ZF2BtoqIx&G6ZoasG-D&NigQG=3gPZk*!#8QeSp58};RXk} zHrpWZDv|cJnD`Z9kYhKG_-tYsJ19D%p!}q5KpU*cvkv)O5_Vzytj?>fUPAuX?GS}` zv{8>ZnUo1Fn#;F12%O#|CS*Lg2Y z2A5|I4Fq6bU32dT@YtKuJHYw<7{K}cvq1U%Jpkz?ndOs?$*a;j(35^VD22S9eRBo{ z4gK}(LQs2RQzB$wsr@w%o^+UBw+Wo5VoSirIMXE#Jf5$;|XErQ3AJPYOX)szQdCv z_m4d`XNw{b1I?hKXE$MI;lrOL^_wR`j%x|V=U#|`3?UqnH3lu{;QU9>v(I9s;Di_D z5SaMQ3*+@C6L?N-X0PHpbfB~vC)dEh6|}BF{2VkGxuLvJu(nx*ACd-ij0%-UL>gi6 z^lNIy@xqO}&^!}fnVePx*s#h}%l|qtGibm&Fu;gBH}GLQIh0^ir8Ay$-p`+>PG#*> z`7_^ZigZ?uUCcZ-P8ZL_mRA5jw>XV-kbO+_8w9biWuo!jB*EbPvXrTE#yP0I{9Fw;3`pPLp zVj=Cg)A#jnuMHjIXS4^XYjPL|i|qV&A!Q4ME8vOm06~ZJI`Da}sD~MQl0e>$szGNI zGo^wwBA~u153D*+1rNoU`IWRe1F@`-Y&gdgP&wj=x~%TjK>0irsPKAW<+;da8B5_k zIB|v7LatGpd6-=i{CsUN=C3*A-CRRf72D~c_dhD@@ z@a8+&AW%{Z8MF6MlY!?v05&`g5}@zn9E6Dw355GD2HtTsCYX)1ZJqMLBB zj5-!9W@x}1{7*tT{|qugc|ur2zMb_!PHm0B8=g~o`6D)Vr8Y8z&zg+CjH7MUpUE06 zy^+Mr^#iXqaRGcuj-Lge{%J1Tu^WFP-yd*#U0NY{;>tl?`sp*Q8iwFrk9|UpI-F0Z}w)m-b)6gGk97i#&9>NkP>3 z8lP@}@{l$#u|aEB5P3Fw+iv!#MXmsig_Q2#Qw7A@mok z68c5`yZV1bh#?Jes}`|SlG+vhmr6Kz>oMyA6^2)hJD!9tn`E}rA{&ohP6Selt^l&z zU+g9{gGG2R+81Q0t&1}i(!6hK%4kr*WTMMz-HYVWu~!?T#)J?klv>rTl@Y;Pn|MOY z;2TUyq5nB}k%N9%8S_&ogc2yn1iH?*g!7Lf4_sWED*A2Ow=LW93HG>Nx7K$T*o~a`kLm2!M~r zqu*3}2+CdD=5V|2#vG0tAc)n9j|ckK;i6o(5QCI}5^tW^h)%>)0RXH5$lQtD6eM;x zC7K+jaB)!BLERf_4_w4vcmPWsjW2B*_hOduE5in5zp*HoKU~6<^r`fKaJ<)VbN~Xp z!{@J{g29QnMn(dqVeq$yz#%mW`()XcthTeZL2fJ$z|Z^AT8{7wV=w`JREhDr0nkyf z{rZ>qP;M&?Y8RCjx1lK|jL*Ah(G7hMx^wt-(8%Y$r0Pq(KvhqU6Z3=S$(tlAaPEkz ztCW~Eqv!_pI!5XSu0TZDEdJ;_?9U-C0(MQhJsc8uL^5`#b+?J4MpATF0C2MMGVE z9)pNg#dfNxU?`lsEz6HJP7bqvFf;?P4&aPXk(xO1QMfuQ*IOl`%`QT_&pg$Ih^vaVDVq8 zvFof2EKMhg%Et-*`)sjZ-FE(NaQ!~smfPfx!u3O-&*9)XLOc{_&&=xxr`aQ0SBZ}+ z1DgC=ZGSbW;huSTQ{=)#z%{WnWf|A@!~+iKsANpOYxy!UiohGRW%P$r|1-k?ctzxd zPt6mvM9*7B>8&4=gzGPd2%9A2-O_;1`Xy!c!P-cJ<7usfWXhP`-`7sX*h`vW5eUm@lGa6}=Pf+-{ef8tOF=6z8*a9lBy(xcs{`l$5RCD#RJ9;d{q(F7S z+1Vv*?<{*j3g2ENH0}7gJ&Tf0B#lm%;cJ5EiN0i{2Qqn*Dh)HMYw{P??d%Z*5>Rzg z+%zOoq30HhG4L~AOWAeD;FBMMynY5?3LS*``otw8NLonFN`&*GzBY%+sH_1PZCuaT zd-MYWO4fzZ-PW$jXxKoi_IU##8mXuD`UMp5q|Xee<7xb_otXXtQ{>S%jpZJ zumbDT3IdV;fAi_lX;(IqniEcSb!l?wLO75V4UhkS|7vRfA!1p<%mXd-kJRDE_~w(N zL68z#qe?-LkPk2)X~4gi0jW3@kPebOEB}3Y_?PBtIkg`T&uUF^5%rs;(Y?@vi)Pwji^Z$I**ripxZ0$_uG20mA`nHSsbl-it!F{{ci|Xjp_Vs`JceeVv zIl}t3&-V1C`*q*;?WhH!rQ@Lc(`pC#q4|lrUZuUxe%M%@Ejdvt0c%@yQgebW+IpLH znls=W7i5v2%4Pb4)y?7GMC@U^P=Dr`PkGlbRCI7xMhstZ(1SClxg1%tzbk!(9sM2Q z+Ew_I+v5?Cna`u_A`^OB(6{Ltv`dO`*W?_|l1F^dvx z>R`eU63ps+G0v7tsHTT6)bbg>IaEr!>Sb7&_lTNjgFVLx)X7f7HE8Nv2-Y)rt+qcfxYMfJG zB1GJ2lUNGEMmj>AyPMX_t(^Hy3F(!t@sL5^DqJeJ2Gw@)JO@6Swez!}%x*cplkVoU zZEE8tgDzWiETahm$8R!fjf}RH))!Z3g5ho^DzeT7{H!M{POA~izLlxchp{;_(24>t z1v&o=3#F6L+zgz_?@i`DwNWVtD$GEUk~y={!LY|?eIl_LQ9kk!?J85KEM)$?I>fMM z&61x>2Xi4+#lSMx8X2TG&D0%0PCLR06IPw2gx#m<<}uqni^uzANTQ3+%-OBd_j#5D zIWJ=TJ}^czOACf8=@en?W&X;FJiU`dRuO82U{rVzJs0SXmoSh*ImoYk^sMx}yBjeF zF?Wf<#1x9Wd`#Y;OOPAf>jo!v^GJ?OS%Z~DXlvR0Zbunp;r|ayfkoNLY@(w;ca7SZJ#aVGvzT=RX_dMlPRA6KNP?p7~JV{fma`&15XV zf$H&R%eZNKj0(MXg|7G1E$f~h&wbW5MnxdM2bSg-bg1)`vY&zSBxR_mU4*r}B1D?h})f>UZ9`c~)7*ww{ z%7}4$CRs70&{PUby#deknS{zgrTalP-=8av}0B zbqHSAp>;12IncPll?%LnSu zBV0)cRMGYcZG*bpa~$uTi2yg}m$|lN&bOPGAOX=D{pHNWWmPz48E}r``Tr63$)P;9 zM@Qw9*dM?qUUMIqp?LMJp7zoF>z>r|@5+=G>bibe%LqU7Pv$WiEwcD? z*qkfR6d8~#_rezzaz!c^HV^yzjpCZ{W7mw1*cem{_Qp@l`=L+9(gRAL#ceZ#U<+?6 zs&ztYtF3^rH2|UKTs_}_{`u!0Q~KA`EDuws0Rn-9=X}i_xj53x;>&NI_pvzSniZw! zHvqGQIF5FD&ANak7&5669g+!kRz@p2{P(-P*)9_4>}%eiCzlpoz#=fl5GHR{b_>Qq zE2D{lOTEULIBcS`8(R*O8Xsko;>38iocXV)+l!NzMVG{75=tb}ANZ;0Z=>HwYZ$qw zsE*J`JXn}}U6qQD(QyAt(*+%CFrkUIU>und$BUOp{h_WPsWaB5;U5Lf9u2xE8u zfB%2~X%HAw%95F3>36TL^Fv&md)>Q`jbpP9RBXB6oTdoC`e5UiW+g63U$`3vc;l7@ zQzG1UOJRZ~&6D+1Anc=xyxnoVk{lp10)StoEC2ui0000001^D?ROw{T9UGLY1*BP7 zseTwggtNWZbZ5T%W=EJu7pzk_SJGsiDt<4Fnp3Y)H%6egPgD-7i2bZ=oq&XBl~H9M zZYibw+YNbEyO>xLKa)`!@sYh^Y`p>(Z7yISXs6b$Skk>a~|n4)B8@dbQop-g4MjU{nh>e zWNfIC|2Dq>nddtLpR93e;}9;1m2b;|!+gX7%GqvA%Y#0{Y+X+w{IA+Wo?U_^(w7|D=7p!gKk!BC*EtP6xye!}v(Z8t3;lJYu zR^jX7O95byRm$HH0j~XN>pka6|0LIOaVzO#x0&6CwRlryQtrbbl2C1Uv0pUXrp6E; z85e*6!C2x+p+b>W(LYSrdmc=bsVDzO)&r~59b#$=Jw6zg zzV^HSK1payYYjOYCnX6dE&~4|+ViOQ*PW1D@G>`qsuDtlg}=QCp6hB3V;6$hyVZp0000000000 z0043tT5ZIMuf#5jM&IhCffk*y=`o+cculiscv7!&OLdp&LF6oe=Y~;?%K{9Y5sZRH zS{l-giU8i3A_<21ez`&;_t7KSrYRqOw+n3Kcn^%BRe`bTd2K&YJ}S#T#uh38XQyZ9 zxjxLlB7~`j>=b48G6djIC%$SKDp2`cF~Bbccl+)-W7sCF#l$*}2PNiH5mQtQ#T5{h z$R%)brO=#)Nh}f%hY!T4dk}8MhF5_5a~33}=mTGB^6sGk6#qAYG769@+Q`46a^T7l z3KGkhkAs6a(JQ(8<3pDOC`ktk=r{ULUEFK98q9%;M}EA))PptWwJM}9z7RFno9S1o z!OCAhVnkA$VSJn(Iu=JYX_WHpe^`cVKl)jz_aCxlZ9CQKMHb6*2Y=N+htE%D)#j9c zqTo*rX90K}Jr_bJB|AILuw;5{-c}@1k&t5Lx2`2S<`(jnUti}`&gGpeg76C#$5WO) znxjd$&bSnflUwpaB<05i)Ontz%{Lj-_31KD7LTx@7nW*&r8~o3(39*-TGygm2na}G zwp|uFWvU?W;x0zsXUi!p`vsW-FC9D~_)qM{vlQ<3 zH*#8}RdteP8A9Il<+K7n?XWfiyFS)gl-YhzWp~|7j~*>Fyh)ht_yQBd5~g!3RpP8< z1z{L|nDzy@sxk*}MTcMmTH1AP5EF=ANzXCQI&P4CUeN-r%blGBiO*^qQ)d>6PLMLI zF{Z_=sS3C+)^sHJXcnK^ky?j>zfkAMBAgcUsp?(5!xv%TlZbl}Kwcdt)m1j~VvLke z_rK>jeijzGf+{yh>4Zqt2eY1{enf*@X=z=jvYdJ6HI{iVFJfo@DB%F2TmXptMe>qg zQi}UvBgujsTzNqiZ-y^zSJnxhw|zB|=UnQM#=BYMG*N>qY$dA9!~<1gzr?KAIQTj0 zU#>M3Gib$-`Z>&zN)bcRaztugldmcb>Q2ZsUjwezlodapGN3q;=f_ll5fWl*pa33f zgey@dvg9rKCXhsg=$HKB=8A6nlS=>|)akxD|7sf_G$y^17t5@X5$LfCLj*;!XjZw=y~n;o-UHZsF@U z?X`CXUI+II0WyDrsxLUT*?DW9_U-~iknK{y^}rnpbTx1ABf=-V0a(v&O$VH zERU-#EX#TA)0LT{53w+s%br1PQ)waaDQFM>eJ|Z1Vj|N;6M3mPQQkAVqFOYH6X&~# zqo2W39@ZZfC86V*C?5k-ANJlf+fW%SO$UN}`)e#4T29$!Aog$PT7;*zA_+lRNe}$0 zWB`$_=`XV1<%PUA3>7^$W(iF}HH}=95aNI5uOj14fkwlZ+mV$Jwz{)_P63jU+rmA{ ziEZ`fO3rHex%U4`m=%kaV0gA2q_=i^Yu$3%e${A1X{36N%^p07QK`%(`Yz=kkWCT6 zf@6mKq!F@W<}GxAMMqoA)JMr}PJSFgpZG$Ud%Tk+21Wc%liBwl2{q|jc@J`Wl}*d8 zbd(AINJau;k;Mwcg8aTC=a3*`3f+`~?Kk|%n5F2mE*fjP|6Ih-O)Z&#gmijw0Ch*t zrb9%NrYQ@ol%W4gAp!LqjYzZwjvY%4$q*mYnv1>b+D6jjPqUFjs2B*iK# zSBqRit*@Y`3={lA#saec2c&j=8TRf=*_Z^(*@i);wnjJhpL#Ujqc-+;S1*#;k}%yLd}=dk^WglKk4$Y&4<_A>(e&Nf zy1egBk|WrqO)6lc@jMo|ln)zbt>DWdmsJgN1E<09fFwzK@G9O0zvm$fD&{1^d~9}j zcK#U2XnqEjwma%7`c2Es!Yv{U71kY0CKWzKOlO?Cl$TJP>Y!2k?jT_$FliR%8c5+n z{Th}o-|OCRXi9Y%-}i4NY6U}pnfnB0NY*!%iTWWKhRb{(=alTNQ#Ln^x16sxOK>old`J`@s~>d%!wlX?(37USUY7!M@F`=`45uG5!{srC8gcM-B;M zV}+Jq6-wS3>(f4UvA7PAY2tJt!2BzHdC*}S(hQL)Wlg%Uz?^1B5E#ZIYGK}V&wkMq zUl^{15%j&>oTIDF7%Vi{bF%{*%QVywr}BQR(sy3^^@li^8t1F?6n$L`!_uyU;u`0% z7&;LGA${SQPM7%}LvCzT{Yp?EF&vR21#J&AA>e96LEFrn){DPsu?La?5@o16L6YRm z9hfdRmd?hNQirRIpo;y+<49UAby3E8-K9EzkWJ@NqmVtChEi4QNAV7{j_Ij0Np8&l z77vm-{|Iye#mEm6e`!|-&jI(=y36WfOk4^tH_Ci-psG$#ZWLtsXv9wX1Tu$ z?l-GCx%ylI(Zc=q*=_67O|$L?^Re*5fcb?1u_I3lcRk-;kw~c+SKXCN6aQ2cM0QLi zo@zhH(nn!sPPX?*_Yj)gt0phKlktAL1&a50Qz zcQD4dW1BgcW?yQYNH!U#!E+@ipL;(QnO*kn00~Kd0#BMAc9LX>8cw~ffkW+Q(v@;8 z#QV@=r2SkRBc2dQw@n2?0z0ZC`zA#1CJ=8!FTKZq@QGSn137(ZXmdcNt;jK&%#fX) zF&w_Hh%MWNVFZ0qO@Tu$;oo|NMOPU5NH&?!OLj+As42`PU5t=&n<#y%gF4-WbI^x} z(sec0+-&e(ABgqbv%!N>Zp;vm4_DQYz4x8|EWArTMSFowP=St%?>5czRj>|`< zE_vAezHNi)>eU}RvrY!Ux1q2^0Fc0Qw-}Rcp#Kai&n@7)oMm76NCGSeaFM)97}Z!WZEvz%GyZI`g6L98^mv~EVyKYq2f+^ zRPQ~BNfu|AL099y1My}QF2*kcsaeLs6!+{?dEIg#DpkXW`w<-JUszPib7OQ`IAOPGhVSZ z6eBSBPnK>`zv^XepUud59Q%YkEDF>;Haht+%GnM=hPq9zoaoa@U>~~k56G*Vvz`e? z^>#`cxPaH;Ui6?O2I`R(G4H)_tG5(F?t2;=;1G42B66m>qZ^A6q#4k;vEq8ioE`jX zY2v$^z*(ic{Xisatb}zhL6$h@75NN@cb%@V?e;6Lm~d3Ob$RacOJQx52`ufV;A-uW z@dqiAED+7vOLwuuAfbuyTy5z6_=p*wV$Awx@p|d!3`-bm5ODpYGi`E?Qj!n0)WN~5 zTfTA}*%64X5)UJeA*FaGPuL3N=oqa*zD%XLsTB?jEdA3ZD)jP+Xu^g^DI?+$!GqG1CqwR&eqTB3kDAlpM~KD(*asp>)+XiQWFsf}8Q-9hNYL zAi+XL+kAoC{@obQ$NKn|{!tT>MA;ZaTbR5|p@Q5+gqC_@xNfi9-ddB=DDt-WObL|< zx`Kd;F#7oYv4CeCQBw!@!=6N7e>$*&Rqjy6`j!aW5nFCQV!QWSuOj9>B*!csE3B*v z)B^FYuqkCg(7-Xv#J-wA#o1d|D_I=}GFl|jMkm}EjXkTNv3yy{8>^ma6>-9xuBfCPFrLS042KfLzEv(vQk0Izy@Hh;B(QO(Zu2i^F*nq)gY5+Z3ma}ge3uFQ<>mWAq5=13CIne`mPVRlKsC=c-)T=-#8(w@n9RY;ZO$cY#+!&;YK6H)lbkVujr6Sf1+f)$DT~Y<1wtHhL zU;k?5j{t%(S(;a7sgViG3d}>b(n)jpHq=Z|uHfPCj{T=Di$hXlTon+rEb$`o1>i0H z3U~da!KXECmGK(*6`Rnx%tp07E3f3=D$GebXCuM~u2&4dbg6^Erj#sSF%&6m5)5!? z+HQ@M$MWhL{SUmLpBfqG#7{KWUG~M~1;u3?)!TZeZ*s4PI@HrcktPrU`16Arrmr-fKyE}6H{|ssoXg0w?&kyMV{cQq;~=Baexar2*Bx z)eOZsQdIvUY3f*0uSp;CLB+*qeqeotLP&OiG+}BM%xD0$3Ze}gNVGx5+^sBHolv>D z>>|`96z!eDq{Vyijp~7zMf@us5HsvEZnWmR(kXhAZ_C&2yhOZJLtz`l% z3|!s6l}OT(xUVsBj*-oB!AbnlL$eV{U9@Xji1^x4;b3+Ry)RE9OP5afzIF2h za)`<#w}lPDIxUm&^4zvGw1Bei6^(R;%hrISCLL%W4#E&dauyKP zh19xKR67{Bl$R|U;&G&e=+J?4Q3P4i2fnrDB_0F&5iAni(NqtfT3Jq1st5v2pQ1Tdghox)W`N4YU6{w z7|_p7rt>AT8(sQ}oJ6BkyJ`!%m#MTG#8fm>Eh%cF1_wv*k27HAleHk!4##k|J{(OJS!EBUg!m3^9i zxi!7SU^f13#Xhto5pNu zH?7~YhYT(MWT#!Cw0_VDC%S_L3GkZ#L9alLZ)46R!loCj_jS8bLbJ5997rtXV3*Ivr^8lu$cw|Z`3wM3FBN(|p z-Bz5hR3=Ils~f560lSxU>omU1j947c0lox8?a%d5;mSqs?NG-YGragniD0anCQNtQ zA|o;^fXG@Y>W^W-^vd-e$xbt!Fmko7z&j-Xb^wIgz=-6EOq^iZ7oMjGCdrdut*M^Q zOgWs?1Mai;ACEO#+TbBp^y8u_;dzF!$TIp16?AHTYtlcw^U{Tm6 z;I?hswtL#PZQHhO+qP}nwtLz(c7AQuX1i4zoa6*2xY4Z-?~{62yva;%ZruDxgj%5w zJFHj?S#^0#+$({0r=KZMw%X+ohjdqcI-McMoWBbHM=CX9Vs@{Du^89QZ!{CaMm+^e z)T<^=wO~-ExCh#Gg-0$!IW;Nj-4>5q&Oab&kwj1vVuutEUn`Vpi@88Bn#UziblqfId;*0yfB z;onxVC|Usk)O%mcIY8Yp;Z7-~)}_#tACv6e8?W~Fc@G$jWNzb=BsFRX!dWEo?YGQa z?@rsrR}4l947ZMQC>d)kF$Zlnn*q4Q4xB&%+YY^7-|)%=16qRhVUlNg7=u%Ld62ay zoYuzG6Pf2I!P7rv3FYS4ambzeS%;XMGAFbGbl>r*r-P;5E;m!7{KD>T&~7b2 zAiy3X94X(HS~h)DEf3rnV7a-T>t8|=0Ou@DS!dPR#X`uP!2Y3J@fQ2QhKX50Zm0Yk z!N5X3i#cs3_etK={nZJWy%^ieWDkJoN@crj<*HI1(i*th);fQ)mwYCRZ##Rc5f1=$ zPi7q83XP(a0}8FQH65>$c4)nIT?|TTT)pm8tBA&zU2|1V`9Uk7KUrYT0|gfxb>(1Q zfu7;9z`)CK1F1A#R2x)CpIEOF8^1d4pSCnu->dGNo$Fm0(hz3c6@RhmZa%F9d3Mon z%L8s`3mx=PqYIMro{i!{SLl)vPn4WV>PSeequz~jY=rWOMGj&P8OT?OS?{!iI88Zs z1M?-ZA&O5F^_U^@ae3~sGj=NqA0Upk-1k7Pip$c=rJvvuF{TimqWq@(o@D3 zzbMCem%GU-hu>RStsaLR;mXzk7@@;|C!VZ6`FOdo)Q&Cg`GDM8tv5k0s1bR zX7kI1se){U)qRjTKfxN4PV~HtcO`=T7W=`PPh>v=0ndtDl&cU;%>{N7|IC&oG2+<$ zw;Bhm`@Mv~nd+;5f#~)&^L)sfM^B#c-a*w=Gv$WJ_nG=gi{|Vv_rGCN>Sv+?utd6E z3hDa&k(yfbfwnMhzL60?9K__9L-X#>3;|5XpwJ};8o*7 z*OFy*X6&1ScFXVszHk{m2y2YEqmMb#zwGWuED&4T=QH51_R|f;tbOqO*zw`v!+(Pw z-iJA(PZ8K<5vSu*vwJGVP#358(=c>mYM$+OdO|2bw0V?8HW;n)J?zg?+H4!?`;#iJ6 zjb=EwgKc7If7mslKfovICb?e;emN#B5$=Df96B`~^$`9d(aN)5W6#_+ir=f+*TF0)w0|I{-)zvx$6BYs+L+p?@N3!m5O>j1s4Ac_ z)=s`Q-3hcFd!bh{+MAzQup-t!PxVuNmoW zFoGpQCMUIOY7l=K0|#?F7XeZq{Ej*2f1}Zv?5!qb1K@0weWvN2=lhY;arL%{FWA*$ z&f_e$><7%-W}+Q~=bK$rF${NmN)Te(YuJub)>WLWjpKM@29T7*4xkac@0!m%#O6<} zdIJU3Uz^ZD8A64SWi9t7XX*X4)p~G)b;LV8Yg)9@_ArAO0qf>kafb(H*U?M}nC4&T zBstH86EqZ!?dz$VkgeuA$uX^s%r@j^NlUrLnV&zBcD??#hTK2&_zNj}&bzL3H#)s; zGL6_x^>Y!*dT+VReX~#}_O9@k&OoGA${NM=7hIa4k zy6n39AvX;ze`})16msl?<9=N)ShOGX;0zY>#NSOgq|RD`!sf0Budnq$H`*-Lr3l6*Gv@M!dmsZub7zJ8Jaq-R` z!D~wk&~wivt)jJMa)MI-q9=kzA3wvF?f}@h(m2`6k?9Ri!SY`vE^kbag3cP*nPOU2 z!f^7w$-r>#^5hP_7AumV1=5;$u};`Y zi){1gpk+dxewz9DZR3v&JyJ3unCDU0pYV{^ptuKKnX@;JTWhUI;Ab3Sd(f&lk3@%w{>#X%Bji;2!_9);GMxQX%M z^UZ#vG_iHl=485bO@3JK*#heZ*(rrY8r0DHr9V+dty!WA6L!x*>YhWa*twdYh2Rk* zpBz!*K@}yDb%tSh6GUHnz55Cai?gA)K8>VE>U6xlBNduA+fC`gQF(-;y{kRoAeHc0 zulYh`I0EN#Bi*$Wdg)l!BjJApDwh1ABW|~$_YxMpEvq$Zx%L{h4mfp;gb%hY;AE`RwdnK*5yS3|A9?d;Z;!8Z&)6pv$Aa(@^E2CrOE=x zt0exWV~@#V-YJO9Vea!>h)v$Y&I3bKSi$UF>$SK*Ii#zJFcde-~~qS{01( z+5}#dR&oPl$D~uX8g;SR1b{5MX(?1ag$A^8<*RZVff=fD7_%b7&--G19|q0nVAlR3 z_Qhal=a7Qf`>}X`L}3&b=mjKXc|P5Yfmr$DyAA^-!l0nxhP!3+(wKEk=5wclhEArZ zML`>gxm60Q=q^bwvXApI-wk1?3bIz8GWX}ss_^{IYnYOG8PpCF)bgJ29K;*H&@Mv0 zJx@DzF(7Uujg9{om-IL#h05K&f9zR?zH^<~lV`wh@b!bWH)%hlAl|?iMpt;wMu@Wp z=vZuxCe|#;bZqHO_BWVd2wX4P5w6#PonyjGVV+>c%NJDhFYS z&C7%cJtljieHPd)@}Z7=OvID-nkqD6Rmixxw(J&Bev0Q2`#ONERNJ>5HeQ52^}p% zWvJOlwua5Rw*_qWz9GYtRPEnXneT9TMXq6OGZcUC#*CmX`1;|@SW~eO3I{o9y)#uu zZW_DCqK^bMuNl0*X7iy2>HBt5PiNh=EVWX~IN;udkHABe`CS&370^FgHgk~Y4KH7n z-6DpS1yopOdJPLxBfATz&B)ecMqNWRNRt!_x0Zi#bzZsKAV~({RK7bU%4q}) zR|oa%{8m(~QDI2du~8u*F{-EB<2E{!Xmvu59BsErr1k6_Afv>mEA_y-o=IqJRA9!K zUFFIdR#(?!v6p4c!^rMygb?COq16c5`>#o!AvKMRRF%jBuF^E2W4!>re^gg>Ues~b zX9SkKB4KjoFO`B_I^d|^!mHxd7=!zx#lT!)r>G3c?PmwU6FCk(0UysMW2!@mlW4z^ zWqY64BuTB_cdp6g=TCA62nZE~nNh!8wWo5rbr1U+n`!Ha>J^A}T;{^VM+#_DTPzA- z7rYseR~ZyAY7#ZAYjK~Ch4`_DMe`OOKbwnK<@mw;y2e)<7xwhN8=@vIStl+1{bPfl zhRNJCYgmAt*?GvuT{K6CiO+?f+vVvL^4I{cc?fcV{2U?8x|7e2ls8-MACZ4yNJtE$ z+p&5~!xB$=bSmgnW54*RW zsP<-hEm_m`;B~}P^Hc*4%10c>>|mj5%*+aWxJmcbDixZCmfz1$3#tk#HPv_AD-W`r zcblp@lV#L7An}c$bh6Guf=`)#?*NV{2tfE`VG$`F@}uNcN(A>` zZn$z@di}W%TR&1al}^AZ@>M*2;kBu9bKy^Pfjv&o>CL6RdYpw$5z>J^@EKnkaC!|l z@34_E#6<$S?oS{(=;J`(FyW%7Jk5NVCFX_k53ddxYWos;yv=tu^lD|EcNwo*QO==V z`ZcHOGB9#W+uf@YO)cG#TJBnDCO8MxHm+etXiJgx02_OTKr?wdSUC2^|1rqE33#e{#<@eD za&~8O`=uVBOElI45^X@iWjoXIQ*Yt>Xp?-eb|@34TUre%$IQ>1KC~l&k7HcXm@nMt zAsR7`=vOJ^dWu9S3C86$>wikb1yg^ZH3}t3J0~e5J?b7*k#G3}Nbgq0LBxiNZ7oG% zI!sX`9}wo2tdY%;@o0fytoK5+p?SZWSstw7j%9M#YGhYofJiMRFGV6fT*^mt<8_mR zFh%9g@sk)4a;Www8x?|Kpm7aWLT;YfzS(1z0bm;?BLrS!N^~03exG{uQdsKdzK)L8 za+?K^!8oZ|O4TuQB}Yp#t;xDy*1_iJszUO0o1k>5520b5j674Wka^5B>w7%>Zgl)* zTMGI;noN0L>UwMM>)UJP1nX43&RXHhW zYO$ioJTgxMjYxB$e>?UEco{DF0f4dVEGCj_Ja0BOd5b+t0Re`!SOnVC3@AjucEx{M6C^3qcJ?9GvufA8_V1s9?LW z**=}Sq0mA_#rL3Y4L2c%(SlPeGI~BLy8#qm5Y~K%7MSp|Cmuief`Cdn!_Yi_2UlZb zsTet-_CREF;4KYo-tysU@&5D0)|cu9f}S2XYy-6ih=1fyHxUy zJW~yy5uJP2fot>78h>|_PwW!|JTn2r0i<>2D)JBDd|pGzi`n@Ms@YsAN>pbK>%E_s zAJb$hlh&Gxd^rZwJkc5mS#7O}MWzpG%} z)=U)_`)ooc$eZ|J+7yn4(41h5=+S;%xjs5vumZNs)B!m zc1VUJZ7YYnE0C3s#s!+kKqt3xOnD+C;Qsy+PTvzpRC&_do2pNrqJjqimf)U!nf10t zvuy2;TBA@dam?jgul41d(!|E=0H-Dw*>Xaf^Dc9gEwzj=$)8^vxAFx^Qgc^{hm;aL z=6V-0;|KTD8srO`!;f2gen3C$#rwT3eDc4wP^1s~@ZKJVdEGxh^ZxM*$vn|Cj=59_ z7nMW`+vggQ?6bTDi=i*(Vqt(2%or9k=;tqPSDo|_8WgTaw`KJL^v9bxAa&$@BBmwC z?DO?C(#9u*ioLt{(cRt)4b0+`k2Z(l(E!$Js~`lMGjci4^obK_Iu4+^d#U(Rh)*{h ztfFT;i75?Zd+K?E@OA6EA6VX8K6F-u*eYI)?r=hIT;)%uG(dV~t$Ls_#TJ%=T7bGM z&3EvIc#uq6O%o-mB0#zr_QNbcM~^_C#0ZRb4AzIizD?hJ3z(@8@5<)*h>3*&*mXXv zMgapwC^bdwG}#yKeiW!#ul1xERZ|t?&~!79PD~9p6cyPBQm65FF^=Z)03o+C0-C<9 zW2p;EjL~Uj$GeW!6G{+)e>TbDj1c5JL_6cwJ_SS*KCK?tap*$h;oUZc> zF`CR#v(&kSYy5cuu^U5fmBS3*OmxSFZP&ma3$h)O1wyLfdYwIEoL)k@!N(oi*DQ41 z>ngTx^z2ij)cW=?vH>)dKW2(L^@LRMyK@Do`oOr2XQo$Lvnc8>f*`My+JUV?2r#Ch zOS&~_dO0ia!f39)@D;#SFDmu$gZeY)oUGJ|s3s@0&11kqfMYc&h1Q>~IOu5$)BxQm zN30SXHocgLu$|+48GS*@*ig~n%xyPSK0hl`5ACTOGV}GPxnw<}P`iZ$X|I8L;3$RS zXcP_sx0p5zjfen6XEj@FLz}t`E6~<|^g=qfT~L#-#@aF?qq=T3WrWA04;sRAy3i2L zXu`*%szSZ}Vhy%Xz48uM$kbCj*D>*FT-^M?e%b+=`LbIPJGal^{JT4Mf%n&R6nnFZH8n8;S*N`$Q4GpX_AG4Tb^AVnivJiI18 zJdiEaJ6a9yTGJ400Z*!KVf3P3&5E)gT8L{^h^rte;(G3kLLrmA5&s6<#HLA`QDy-O zu>{w?Gc*uJ$5lOjdw}C^JyquH90g0~R*3cX%{0?y3O2)_Jw^laE*%k}nzQLKoXg6vMU79$&A7 zapq8t@y;IP>3U7he>P^Pw*#H4&pLaT506_*L;!I#b!kw6helCu(Ejz8nY-xxlp=Tn z`__wq)|{QsAcG*p6$BUiDsjOJU)Vj(s))yudjGH~L>15p<6;xr3=2tG(XOgMYQoK^ zX782Nht-u+-k|1JGT=!0h}{~4bJGCeA+=J!2HtRO^GLpR2l|MY}(p`v*D=5aE6*g2pl&~0YO65A4I zW60SAR-UpQ8e3TxQxX164Mr3=z4YWI$`5$!8vO^{!>71yQ|$}-m%j~uliEi}ZJFLj zsJ}MWzk~@Ti5Fyj-H2Z#Zk)Qo0?@5y+HfO~k97xPB^+ZvZh_(bHtH;%0m6Wgc-hg{ zjX7Lm)5(r^t6n(Vj{rw}&4FN$AFMCd`NDW)1zWW;^9@Yk-+GO6QEDM}WSzyarsCQC z#z(4djTj(b>4KM+E=xQ)j^XjYH4%chG2U_lAq|Ms)0!P8P(_+>mP;}!1p=nje}4<~ zs3X)ES8tmwX1kb#gHXTfvJozkZ~8+}8+FwzmYj`cfQ>dXhWCYgt1HUz=Jsmb_wb$`c^>P=2fa;aOUC z2!^0}@?3s#X!>x(A?yv(fQw(PL&*q${F?d_8hO8@vP5sm#v7ncCiMbehaQrZMni8u zM^EbJImghmFdiE)%qsyd9+njI@=)hp_Q$qppz*zwSdQyhqAab5C;<1}ELsGsmBhC2 z#GghB*z6lq+cyu}AXJgxsNSK(w66a?R`dZ(b$NpKPG6P8auf#At93b{*1tN2XDOzt zDaotP)PXCqOs1fRwQuE69C}t<=+7C|05LjAK=r!^ZyHq`tRrd zYY_Rrp8ii$>c21kKSEJ&kpBTijcqvsAV&FMpdd7GamB`0BlW}T&g6s%wvU`3$D&fafW z)lyVt`-QS<*UE*26(Ja@6C-kS&9ny+kQb#!+4@x)kQANhroxJMp5@Dz7(gb0@vR$I zr3m(18z-E131<6VC7Y2rK~ztWfXo78rrxa8WPRe1o3_Uc&6S-?BAh^5t@J;jRSXpK zw*|c99h|9)4+Ay^QXhUp{tRB@QTQT$9xWJCN8ZX}7|{bSMmC_F2@<^JT8+F*jpyTnU+5JOI||!Yyfx> z)5~t>boBYlp}3tjXU4`VMGC-Tj$rCwcJ(?ppbtMyvI=_@45|pLDoNUZh%`@nSn}(+ zA|P&+&nvo`I@GnO1|{rx^IRb@>y(3xu;Olw+1R*IJv}|W84eRjpRjehbE%k=eV!gV zb7c{^IOL95Jr(XCRycHBPWYd;lm8zNXrVw=S}tt4T5u(nExwqNj_O5Wb7Dl`MsrNG z9}@L;d%olhM1$5Ne>j{OL1OXyk6@`bER&&kwtA#^cVQlDfspdv1M^!8EwSNPr-$dc z?yEKE`|TRdH(;X>12!^Csr1g6_1? z19)YRXbi-5Y=Unlq!aF8CLJW*=1j1SSC#)e;i<7JLzX0 zr0I27n6u|g3bh87CF1BSViq-g`JH|pqb-(eDMYa>P@gRb4SB9`~DWfMH$E^(s~LmAQnsf?-q_ zg@gBH)<5BCgP1Rml{K9`i1-TeS4?W)aH=!fc&kYc(+qeAW{8F*H0;}cKA7(B?8y2R z;Qo7$y3!FQcPmrP#uRjroj{*_1Mp!~#Ir$pw2B(GO>&SSOiicZl#>d(SAxv8cZo)r zjrIEDvP=QbVn9T(?FMJ|1tuL_C@xoeioHZr-tVzH!a6B5@)c5>DT&d{qtf9w9 z8i>55pB7Y!OcPOF^wt?xK^|*m0)^8uWy-~Xnb669VNbgCL|#QzvsC3<7b~O{jE-*q zSS1U@Dw7}O!aA)?Nruajni;G*G`wGoB4MB81(krZYNc2(3B0~HWMdZbws|@&*r;;C z{uyWQoP$j_V3}Qa(*F0q@;=h?e@g8CX;1wrX_O;dKr6)^>mlWV+Xw^Ub8X z$~wje7O>KccKc-8u}d}FLOVbfF+;lVH^r5KD*+$;3*k}dGpV7TG-0mTvj4y*UCb#c zxv?HDE9F*nNG5X0Ibx4;#TFvvyq=s$586^tRgmpg%-eFd17YBzB|2GWS-P6GIeiLy z@GM`GA10zXiIs@-y zgqCkhX$_q)=Q<(-Z&lDr$b~pUwy%_(xjm7PcXR{n@xN*InCvkE4X*E)7ZPUN2?L5l zqfGH$Rcpy5`<-m^uM~J}aq`^$Q+{Fu-^BSRKh2i+{TiRLmny~|Ecy*h9DDzhp9FvO zwZ~M)OB{?Pj|wrkLcygtjnn_ZPe#<9U;Tb&s(ttpL)V+-U+jYTp=mSi3T+{~nob$^66b&S=^qoFajqvR5adw_*Zf{92-P3_-uY ze!?it7?QJfK&>@t&`(0=K&br9{ZvYwMjZUApX!onqV6($@qj522`weY5h3$sKqM|P zJY1*TOYHmTvvYA6#jbKXOuxo8+<%$}$HDSWMGC=Vh+_}kbfoH5^zopQEvXl-Du&p5 zx^4w-O~QpxgU6yh$|2 zTgfnH@y{c@K9BZ2rcFai0s=N_Z`0hlk}}aBR3ba{m!W`-UYRRg-->9I1?qU(E0EYW z_EzYcF#O``nbK}CA$O0EdUIPxMKM?30Jo|3wW1pVe97SQ$@qKbYaMi<2Tg@$C(aAk z62I0D(MB1JbOqvxM`sIkzad#&C5wStvn`VpZO?USo}XgWqI@<9zwiSJM_fEwR^Q3* zqkC>-+)^|s7ET>SL^wsyxoxy6NRZs>ltIEq`hFY6qk=@U*eJYsF++s^RG@4+f;G2+ z1K0zZP1bc(rOdROWNgZ?iaM^y#H9?0HS#%f(qJ@jVOwsZ5!%6V#9#3{w6qNDp{w3= zhtn7f9(Ovus7ra=nttKKSn0qmmJr%z7@QPctrbI!D6b<8fsda^VK#O#9RkdR)CICW zSuFpI$pe)7q{*Ag{(`sdc{tcCZT=MQ6NCfjpimC=0R%GDlJctCir zH>ke91O3=^Kn408(bY>e38^5p%R!VLK7~M!-h>tUY8n?=qVL(Xt8`wgQbQpl#hvP5 z=}kxMEAbm`I6Vn3mcu99Q=80jjjerzZ(hWsJtq($nyVKK!%UENvY=@do3ks&{xReu z%$>?8cOfl;qoYurPWb_JHz1DxT5DkG`2%RdRNQIWNM&6xUQ7pZ!hGW|zpOc8C{0pF zmUGV7jmUuM!aI9K5^2zh76_~_x$9GNls2@>vaR9nl>D~+0; z|5PY@A58(^i|+oB-ENKG768UVUG%Yoa;Hx(Rd@yhNzLerMFQ`XC%lDHiA{GtN5i3} z$a0DW;D=TQD)u>~`*sVA2)Vw8;w+hQ_eACNJzQ3WOqX+ zjRvlK1E=QoI~o91#p;Q2BZi;PXSut$AwG1aMj3@8=8kfrEWjAfhiE33eJ#oPt5GzF z;M@6^OQruXp^D7nRK*^DC00T?$7xl}q$DTtNFAsV8uSdg8TS#~unST1g&HWtaJ^H> zr|8*4eo`m3@5v)grMH~C=~5l-+<^Gl(Z48oAcGl)h}m(nvHIr=*z*0|EvZSYD|yDb^ZhI%p{EtkyrA z(RamWRt5Qm`Dq*1o=s-%WV%3X;n;O$z-SLi!2gDT3Y;c; z0(HPyaQ(}!OVp2vSi)3-!z5)#{^Gy<3zW{_v`5pWYF__cz1JR<5@rE>Yq4&}@B6`T z42{o;AlX(=XiL#j=~!$QL@zy{4=I6gJn7psfm8R<7Hy$Sh{O&k=ZkZJi}$cnPKLF+ z3&%AAKVrj#RP)#{i?sYcDV$|EHINduYqnnfg=mq~cPK|TmbOdZ_iO3M=J&y*w|9>B zq54i*G^>j^#CwZGYOKVdlst&GzfF_JwtI>MLJd#OYM_^M7$ZqFJc!L%U*L1+z|z&n zCq!Gs*pBzJsK}vjRe;Tp8(ribM@HXv1t{GiK#MIVguOw&$b0>v`FLY}4 z>XDG(Ek(IDGN)csBQMYx_D_f!##hbh{~saBB#a?9SJzM+ZUvpL3y2BS^WvY$VVvr$ zU*kfl5Skvw_uT*LRBRqy`cmPXmPissHnY(M9K^{q>#mt`xCczAJeV1fte&ubV{&Te zSEAR7W9RN_hG|);pIR!SY5`mlGgVe0io_3G#g5fU+0khflJ`F&>h0+W0Uw!P9>OXEsRAPOO z9bAzLO8wvUh9#u$`)8Um-EPCx)Nv2*SSmH@lt@9102V=e@&yBzMV`5Gea|%!!r%RG zn-(6ufuq+WCqxmU)<(K_Abijb`yw1w5X+6jLWM@MZ1Tzv7KRAK~{bA9H z(Ciyf$aO#k?{?fgCz4foboEe4_XMhB6v(B8)y}iLXgQ0Y!@ovQ^;Py4^c(WKZlqSoc(g2x&CLm5Xxc(KcWClpv66 zvzh*@$7MV^R7u05$$bs>LWWz+D&Io)KI)H#%>>5X9TNIKWE7ecj@hT^;U9Al-VfYS z62imS9PO9paNWxMd{hYJ_=|$Z7ur876Y@Et`=N}v1Forwny`j8+gCiEhiXA& z3beqQ5@2I`5J7BP9zo9p(39|w?raX}$Ci)7MZb1bR_l5g-LK~XKBcUMc}Y>(s-?oW zoYmL}tjkXQ_fe(C3B`YIQnZI z9*>V2a9ZYY6j!_*D|M7&+lZlcF$~kPK6bGEkBJga_r-k#r~$LQz61{4r~ac2jPhb{ zJXlFJEb#T&zpNJXKI?wa_7-29!6r1ZDh+YBY3<6u*XqR2w>sVhpHYWkSBrZzUDT2X|};J-(|utba=%2B7K?#%DCK`8ro1gLd; zC0Yl!%#+9q3P#14bE_Lg%jcF=j~|FIN8#^Sfb>Cc+iHr0l8k2i)YD)ObJ=Q2@uW;G z{W3l*9A?++`;b`r)w-ZxwRt!jTlQuD)nw|`t`#yF5u|sG0Or6bOe7eTG=*8V3yhPB zs4dB^=jc#Bjs=B%2gi(k`5|W2&b&S2eqqY4WFMrM><(L4yP(_3ziB_@QSyoij-Ia8 zs}`q}D@eh*;nA$Mn;DJv9}G&nz`>IR7v6kSm!Irz4ve`jz@PP?pto=plDA}2yO~LV zD$z5n1N4*`F2|QgplubmdC}3fk@h-3ZgTr=r>r{a0H$h#Q6)&Sfbc8HYn+H6fZ7Z} zKr#X%Mrw=x(17#2BExsxCN#`~k^=qH4%Y|TGfJ^V9+uaAs$TXGZWtq9?wd+|JVa>n z1k;`l2jp#Axfd$Cq>~zZ7xMZ0L%E zj~vZK7d`P82T90PxQCy=sB(yGx{E@8TS~vS1dN!rkuWDw;&3ft?1xlGWF*H(lo+XC z9MIjH%_=pi(w^4A%SHDWOTgc03d}NZG3o3VkYhM(fRl6g^!Er@2I5(&EQHaL4w)!8 zV5h-0y@1f_Ta_iBAp2wz;RpoiyZ#S>ZvpuhZn5H zL-h@$U^Vc;dI-IgjRjF;Om34*4bAVU6OgLmqqLg>56-ErHHu0xI&4In&0^dmd_88T z-#Og=5ru^OQ3GLf@B307D(aHaj=Bw8l98{em2OA*inU}{gzm31*IpvWD){C&l>q4< zg&%)@koUG?;ly*(I_j~b7t45Z?V@IAk(3hzrv%SzE8tH0SvE+v;ve9|1vLbgWz%LZ z+wZW>%=tb$wJJ(k)*65}m-uqm7{HSxDu#A>-Q)T2=?g9W6%(<+Cs+nBQK=t(!8kc6yt3R6s1VXFW1;W2Z}ef+wdoM@`P#j4UrUkBSYV-j>+j)Jm+5k z^53XTCj)17#JwQv6JzEG(Oy`#(r4a0;RKM+w2r-5zHrDydLYmlkmg@Plb4Qa4_VG` zQb@=JhhV>^3+GKT7%h5rb{p+y?)m8brfVkZh-oubNp-Ud(LM_?c;~z~CYlg;5iMaJ zt3=r+nh{}ugfmsR)6#FWg_We86;;x;LbIzeWkQ z#Tp|wAyA=#?pbnlaj%vR3~~k#la;4JHKC_qa6d81dDT5Q`}r?}M`CVje)t&q9zkg? zakI8KpiW!IT0KwJ5$I{`<0NfM1B78&0fqDS@uOI~Wp&F5CeU(>6M)3YK~*z%h4%?tVwhzWm(AR z&&n(9{L*eVBi1&QX?suJU8!^IDRtSc93$Qz-X-`(e`t-&N!>54V*h-TxLR3 z3ZMP!96`axNb*fs2#;U{y8@NJ#VSj*2Zmt23*22T;5_3q^jz;r84gk+C!%9kv2*iX z5jmwpJ%BP3hf(kkp;hXMgZ(nT0e!xGh-W9q`)G01S+f|3hD0w0var|Ss(%W&Z#`$EK)jI+^3$OX z+i(r;Q9L^x%Jrd!RnJT&z0Uu@Pc~<_rgLFF1ErY=tMCk{Vwm7Px}YhNZ}y`<71tVAs1lPhn2(}vdCt2F4*EZ~Vmld5&S41&CeeFX99k5yWxz=77i z)M<~d+#^SxhxiB~3WeDXrjnyY#f}4hfErK!l@xGpFl28m%$^h`Wx7Hsk)g3Z zjJ>BXi|^rR@uaA%#rMxOScFsAO@x-qF(pJrXHUzr8xHzXQ~*7Ne)(h1mVTat<(4b|z@e z`^#p`p6_t6Lg#EmmZ~Aa0WBVSjaI^%JDkOWGLX|;972C@D&?w$8q%BOrMioPLeS00KwjlIiv+zhD!WiO8yH_aCko$>YI@Fy+%6xy zOx!03lttXO7k>%O)k#@Gi@$$HpcDY z(YGr8RXY+4uay_yUJ@AIdL$tsOICJV!8RRzG<#st&#K`*6pDHBi{~8(xu>bvQvqoR6Rz=eY!=BOkA|(e;tq_7Uri6x=XoHI1H9 zlj$4wRkl-zXqf)sggARZ(D}~n)B44Kr zm7(*v7qcb3+^+&28z;?0L;2v4u#QO0Zo{(5kPEKGw0ZeJOG$M=W=9Dxz)KkF-R?|B zF2FR^LUXTsWW*m#8orv^_FGfi$gn{m^DwhZ?o$?ZDCoGq8>}C6b(0U&bO<_R|CIe{ z4-`pOGzf`e)B-LfSDlNo+T~yVMBNbM9J3OyWCIs7;Xq_-HoL)68vnR4)P`77_v@O& zW=+D*TQ@RP)iX<)GGYWkKe;g037u3beq_T&3KmQoMj3UwhB(9EmgiPBQlF~o=c1nE9CFp9Dk0&$zeGs@Wj&)y+5}Z7>V*Lbx^(OX{f@JGcBbmOv zG`k5787>69U-rViy(*a;_=|R4J+iQK!%Ak#1?sOUv<~vX=&Zsc8f%T_>&*j@r!4I(# z+hI|4{yP?`wQckk#B^gMvs?xmw?D6nJcJ70{7R&+rLm?)sa>YIZ;CH+O0ZZfSlK%p z9QP`pBfQ#i&D~JJOmH=;j++Hsg?L2&$w5j7k6}PN@`aV7{eD{S_>C{R`FWe&lZS0I zui5YzO?pBT2U>u2w%e~FA9V*ajsH1GJ+OW?;AsZSRLjF9p^t;R;YRe(m|cAmgy!Kh zf&1MeGi*2Kr&S;PPyvVq2I*nBcBE({r8#1{V(rbr)798>TIt zQWXcVPpnt>*2+H*6audqWqA2R;jxyn2M(sveuGUT-j!@9Z&O_c^}ta<>5)bGVyNDiKPN~wNv?euk_n`UqK?crSpY!oN`UU8HQIt#4m zNO`FhJ18SE!9XdYVzID2nQ)(T*A|dCI4294;T`;e49omsIK`@UxOG?CF`fmG+G?B6c_?84zfU$i8vc z%{H}D04Q8+#SeOeP(~3jyILigWnA{KZY9*6UvqeV@ud!F9R|aW+s1NRtY9pp282lP zmt?zPlKWkYIs?3mx`LObwA7r7L`8=L^#>9 zLPl9LvV`adh~;@oldcDc&EL5}>k0rDc~1f?3QV@E*(bQUQK!=9CvHiazuUziF?|WC ztw}8Y^eduP3TD79n6@elP(7;KxDE7?gUd`C!m7u+D>D?XFp<6}lv|olyIRRSqF&e+ zbI*N$=g0L!(k)x6w1KDlJf2{5$rCL07d7`23Iz=$uhxtySq2BN^!;xX`DwKV1Y2WfGZ|aM8_*YpU0}VA8waZ34xsK@iy5qRK%v`JU>u~+5 zSm{lcl`tm`yXJ4K%b+5y?m=;5pDsEdN9dZujk&{gFFtI$)*3#3iM7&Z)~#;FUEWTM zP?|)QCi5;xL%;n@00TLs>MFq@1oycsl!(pS9^kd(XNxb%z$x&t5&nxL;u@v7qI(KZ z-SYUjUp}XMuL%}PwTVZVc~XrUZC5+`UjSJ^roUR-K99L{scx^59Dy#F1Wi_pthgcN z7Nh(|dITEM81To7_vps9L#txv|4NS9yX`5wMGo|A8I8#+SY&-mhuBx=SWH|Xnz#{4 zYwga6O>)Ef&(@4fz`sS0phVAHBOT-S;gh7Bq?i+fjXYqCj0l_P6>`|5<*JlRDzLyE zXAQiSgli#fL3dIO7R#H)mKR|)`2Dc!aCXJ^r%RKy7r%tE$G?5hp?Z3iQ$yh4enHnwUZ(?!T>Cf1$B^LS*|Kr0 zh^U)oDs6yMFi!PDu{h(rFyQ-!>?|kx;9uD!95QDt*X|4}5fEAajmJ3+YLj6ojAP9I z1p>Vges2DwY*yS7W&Lc^y*(D$+7_nQYIUxU;!jQhNNBkJbiitm^(a5RXzGbwyOA%tJ~{<} zLhx$ZP4k}SRtp%%V|{_5QNLQNh{vOT{=wwElT*2mnAJt1+gTr0^t-uJ9i<$@^kbXO zoghT=gV?)KHB>R|P_Wq>FaB%1nT!M@e;IPqC)PLXqqru9C&2mrCP4Z9yg>T8wCN?8 z<&%!dtI|5qg>FWjE)fE3lq}0;qM!{D;nxLp7ND3jIXizd>Y)FBY%u#x#6bAg;2L;f zX~U^Uz}t43O8e~0xLqA@&N4Rce=5s(KR2Yb=3;aX$?><==p1Lvh8*{)Ulg7EyQ(#M zOWsCh(Gzr7Hfes;YX;mDi*DkRISxVY2SIOqN*SF9kC|zdoZ;;Bodz%A^+=>Qo&H;8pgla7ufR4zhIHM-qD{<~F&oZhzY}!No(|kz;^99@2h|mn;sW;77kMwV zl_jQtA0dAacvEKKuYwPvA+;bH2TtT1i|gnNm+M%J2tO6>QyzSGjAAS1pc57L&3nWJ z14@L2ZPb%BIk-@&`ak>KqLa26dXTYHpezm};0*1rdVHKzC#RCJgY);yOKGu59Q_T` z2wEH=Vy{wTGwQ>X`ix*~#TS5dDO!qe-@C%KyxMSapvxw# zl|s(q4l4ws_V0<|XfldGo?TOB;B+A?XR^3|O=@)ZoYK5FGtUYJ(9E5*ION@2Lv|reTE2_U+CpfNQ8Po#W1nq>x(<&gc2 z@EKFDd}BL{;Wb|A0Mo7&@n6Qty2o!dgWh3jt*lh7k0=XqY*HYerPB6x%WPBnGN^&m z+9{je`o`Ft)E0t9m9AeshKT5pz!z-70=jZ=jTmQWnQy0uR(O4!7jwr$MaM8jgYydW zpZRXj6Q}6M!=!zbUHFsGuq=3C$9>Eb#y-y)3xDb0-HNQ6p+f%~7g*!B%tG#jpQdv$ z8!FcNlb3QDWMlhV{Bj{)MmfPJ3J^xN6|HCzQ6oOQ7-upm6}QuUq6Ral(g@m}aQ-(l z_#M1@ncw-9&rNE{sMDJpoaN(X6OwJ`D_HLy4cWxIMwVXb^V!WZkn{}1Lz=H7uGMei ztLY>Y%WfW%AP-`Bxf_}IY1Inq42F_hM=@ zY5z~R#*O1Za_nSdX?lGBM7sV#N1$450q zs{TXd3ldc8Z7=;(_!{ns0Q`y3i>js>og z*o2^uUz}}4$n>qaRbOL^9KtGFHV@d7)EBJc>`7Sv1u1V1WH~vqSjqbP7Ch_)njR3& z7*UPu1KS7}EXtX*;>1|&_A?6hT8}C!?b8#maQt|$HwCLaG*0KhHxX;6Bh`HH64Mej z)s}Gj|8vw9lJU}oGgjZ1_u$6j4toy&ax3r?*HjuXB2Z^LB;ZzJ4=UK@M?Sh}!|kKe z8%-FDo>wB=`nMW7w$&ij0_ZTJ{HHR7x}4PMloJaDJ1y#?m=IvH_Jnte2vgQ+JXs@m z^{E2;u8|3qhTV>}!$*V44RvUnD;XDZQ@M#lE_3lP=cFf+Kb%t4taaoq-Z}2l!Z5Qc z7^cTYk%~XQ-vI_Q=dK{j+#=EFonPI%v>DK7e!D@}OXUnsRD@f2is$>mB`a)4&>m$r zgIVcCw2eaK@keC(5%kEH(w0YFcxYlaz7{E&=)1*Ey6diN+6nuaS(DnCInHGS(3OCx_X*$`>eTMf;3vu zId)tCGL0{b>L@=I;&7nQ;7?Oo+Rb4WhaZLzlu~mb$Sw7ljU;L8#OHrw^27DM4nT5x zfdwiAP!0vWAk=FBWC9j}I+d7{`wVHbM&nHwrV;uCCnz zyBek^bWB0lnL@17zwP@UE~lIPm^r&9{iYihlDo7tf8oMKRA%Cn8@f`;x;{G`qn;e?WMBE8? zsM4mrV`~~rXpBjNOl>YrAsucLr_x0z!y9s<>X{st)C)bWsAQ5+TeL=FUfqC$QrG6~ z(Drl1!t{Fw)jsaVS?p7-QKs>k4oAA*cO0?-N_g-6tT{l=5H zz2}a^$GrhPPz)wpmEy?71m4Nj2pmpO1|3@6(|$lL;^6$yej~f zA7kq6$tfKx=OeUwcGx5lZz;~$ep!F`@6?!3^vq4dt}GNz^swt84!RL&2_@seU(g{R z^(!7W%sv!&fUQu_k>YUSE?rl@Rx;`?^j_;opby7hg%0%7}lZ~eV@e%^$C zZ%jCT-SGXrN8eV){@vpBgeolGAsn-29Ot85&ld*=dsAc_*%v*2B8vJa$Qzcz&__vf z4PAuwsRMO}*I8(okWZI>j2fQ#^T2mwFI!*_ptpW!X{AIf?rJ3rl!`b8!ysWs7=Bpz z=sWYYVtejON5+TQQO>&Nk16WT7WPfT9bMlPKhj^Z&DZ0qk@$>3?MJ^s!`zmWw_MhV z#DHo10$XxU_dG<=V|>K$`jh4P-_;|wr0f&r$1~s0fFe>ZcJ4Sk-DAYSJeitgNj>mt z_#zL4bXxGNf(1Eqc+LE6wARIi22%W%52G?{Bb2cI5X4*K7^$x*KB&PY%Zu%l?Knc{ zl8?ARI6-Qfn|{Z!V-9oL<;t}%51}W@)={sSyUU@|yqHvFt11gb&9fbjtHlxxyq+f# zh9C<;nXn#S^9223NobDwUyF-nQ`dTvt*V>s+y;!N&8iA+Rv2^}>wt->-{3_my^!=1 zR)pfuVhsI*+AXNJ!8wJb93i0wpM#VB0GM62{XOAzUv6h*Q+*B29;VF*axrz95?`ne zca%gfPxy7xwq8+0n8Q`R`DX%ldt(^gAIbNmizB0xUSFF8wyI!Gij*vFL)X%r)*PfOW?c-;Gb_ zQP0r4+vcb3SQ0C+i~5pOs-~=i_=PV}S;nl~(%lwBYa@+Iug;S*5C(-I5_`6_UPZZG zX}#LtsC7HWKVtoezk7pCx;WA#+2iMPP-aYa-`HM#NesxS&+Bk=Tg(4HB3pTc5hyk} zI}FL6tHi^3P}-~$LWD$f5ZJA3%q`;Dt*;P|EL2!HQY%Rs73k^zR$flRNpHADyPA-J zEuzxIz5Xt`UFa3ulWJo5ZiMLT{8c04p{LCB9Pe(?nj?{@w+)2`+x$s6 z)Vk(dvt&b51QJc7w7MzvK5IR*#H8aZr-7hl#1R1Qz5{WA2Ez@Qm}{k%yvPfZwnCDV z&Zg42k`(n_+;+Z0E5i^(8?`Cu7vCV6`-Yite&pG)u)S6PKL;rlJpUZ0~*RJjj>@K%4|$QORg5E`2UbJ;M(w&|f9$SaR}(mvU>OIe!i= z?us^!h;(qJjJe~{LBLw)?Fd8|AB?R-V9%MGpioG(=vwtwb!vUS;!ncW3f3%Oe`V4{ zICRqYkE`*^TmmmdQO{8J7QchSY-FK6&PV#)naCh4TLdWlmekxOvHFd$?5K9UMt>p{~#i-)_&6ASn6S48q=~1dpNl z`Tsu`(LdrbZcEM0Hm(lFH*MJ8OO1g_IOi{?&|d|yV6*w}_^+60$WgRBJZ_icWtHv$ zvJv^n6V_{G?dQzzUa@d4;Zc~Hi2pz;BJ^c)d^IdE`cmW|D&v?+Kh1N+e*D>hqJ9WK z*Mz)AChzJUz>^E`Mw;NZDH--qGXGUXQ!a{|VnK`N5e|s2Rim5~A!yC+1h{Gyc7YzL zq0o7m3>tGPiAp79HJB5uPzMIEaxt`!P zeuY`CVXX&X!~oFk@o9v) z)w&>D_w}GFonXf1`1%Iabe$IylVKhEyS64Cv^AFSJ_?LD!+j?C@5bOXmzR`{rUZWOd8QxH6a z-)P#Q-(azE(W%)qEyX0eFNh>K6f-<7iy3*_C(_VLI}IzLGRqRcBYPq4DPK4#77 zWVH6mv?UBLk-KI6pWP4wMP;d3t(>P2igzJ`Q2lA`SCF+4d9IPUr>u=!I=#I2%YXlR zBsiB^vpByf4Q3KxznqlM#@h$;AcK*~_2@I{W!yYo=P}cn&?7NK0!8+*R?0hU-Z;!CwBBg z9w+ns&c@-qshqNo7lVbnqn)Wi0_vZTyUj|vYAekzdDQAu3nWA1!WvuyP#{%7XqavT z%Ys9C6vd$*32?uq{{26z+E-<$eLLYEEhxcy#UQdlT}l!W(PK+P5Hin$!jN>KaY4z}@E8CBY1dQRBk7hniuudw7i3b6 zh4GxrVGhTm`aCz9utyQN2NAdTw=kV2 zbSR`C-LUVUkeWh9${vB+J-THDj}j|YhuE^2nS2uyJ0}C9uLK>lk*(R;rxVXJda$#I z^;AeoK#emjlW=QQ00z5$IR?XdZ61`qj_=J;fC4w{-AS~@uZ}K5YM?7s8h5g}O98id zxKYq6l^E12s{sH=GE;XpEpDrg!jWN5bYPV%|dbU0;2e&8kc@=R4;&Cc^~ki zB}?Je(Vz}l7>Pdk*5$IWRyRDIY$O%)FRP!U%~}oqx;=7Pb_Z8F7A-LVpk5}|7+Mms@*Du;MPY7lU1bCr_nB%wvxDQ zg-ZWVg0L8?D`aQR#qQ=bb5cX;UM+0AN;kdGod0b4g83#XGo~hFS}|6f9yEr;ZM3GG z0>)q9J@z!7r@wxuB_5AY@(N%dNqKc8W+pQ*Rf3*F^M{G&A-ukoinl8$#$kPahu^)k361OAse(*?o$#tEK|V`>C*UczNkhpZ9H{66PuQ3duXxWj|H8|>5<`Za!bw#mVqZJ zqyE}!x}C65YxXTWn5E^qr_S7TL5(6C;Db(=XcH<;P!69@jc_G z3}B0?JT{1LR%BKO$mx%uW7na`P)z}Y#+vx99(Rs8ZQyD)V0;1z$*1*-+$1G>u|fO#$42MvSQgqC3K_MbL70 zoMW6H5Qxvh<;pR(Wb~+CW{dqaf|#Dm(d?P^8vMvB0=-k)jW|LJpL3~=rZo;m2cs#t-J6Ljg7dn?lFP~k;XHc;uO7RoGU+`z@UL7 z!sZq7dXEl&?~jEVQ0sE**fadKBJbzC8891Y3u5dc0z z$T_*XgW^T#=LP9O@)sL#HZes>_NNE}!ax0}G0S%x^%J(qt`4O@4^qDYT{PLC z0hk+Xma_3N#WZtF6p2G82VHyADHICOJAC@ve@0uLCbJ#!y#g`UveW0gWs}2g&fdRQ~@?>fy&wN-% ziN37q=o`@Z?fZAGPYO+`+Sv*;tkjV}%dlf+>6sYIQ#TTeb$Gk_g?hM-QK1=aN;ZyT z2HNzN4micH{Y^0`;JTaxfqzF?j8O++fuLcEG#US77(yTm-z(~VIiWRb+>&oEic7Yd znoL-JN{1E_1-e@H_xY|o&)7fJBK^IL;sjc>ch#e;oQ3Diw7xQFwxIuL{aGf)oM728l1b zqjqA2pKKy=FR%fWd~&gDnAKhi_=||{2FUHeQjF+cI&63L^klNg*H3NZF8)BYBE2uR zF$ikTzGg1vty*o6;e5_4zc}d4n>;Zh@AU2v$BI!5v6Ms^BU9>nMYWl^>z|e57 zgABbMgiVn1yNB&qvyDk4Iy1i5HdVSoUu5puG>7TbPw-*~Gn%>%=#mW4vsbb+q?w>z zKtRv!!x;PLsvwK^;5Hw61dvUWo3e)A#X=R3He^3DDqF*Qpxv9`^z{;XrL^mpB0Qvg z?-esA#J-apxEH=QPYKAixuTzQry^gFWPGH~j6kr0r`WTATiXw)<_k566&nYf4_?L4 z&%eve!MAE6J6>}w*}h+NaH0Ycd`S19tkxeoAe;Y43h_}u&TB4I2Pwk`0Kyzj0^L*c zAqN{5pY(C~W>XYLj+vAG*Ik$UUlr-ZbdFpkB|vV}{txkE8lJtb3K0v|>8r~gj+0aHw?;k|eQ<4- zcy(2ZbOfp0w?$8<#8*r7YD-F7=5|z#BpiiqaH4GY2xt-6^}k3Lq*Qfd4wt|W%PV|s{UhFW(iL2 zaht`@p<@yU@wp8qw53uu)qM|r(}Q#0tB*sn=%F{2cW%;i@R+GWff@}c$4mYVRGXXt zJTp)@U=ZR`3SIax){`{EQJZgOJwganmV#M5zl?^8eGz_qQ1YA=JIK%)w}3&|!v~GB z)TzOotnn7!7zmRdpdT7yw8&k5ZD%SJp(EB>Fse>bjq$iHbVwO(FTUo%RSrW4YIyM^E64tZs9ywE)=rHS`&xVYY ztu%;A@vgM^;_Tfi>t(40s4uS!x?R<6hWN&rGXmd0cSM(){Jyq)bb&hM=C&glJp{W;LiHF=#0Bq_H>xYcXU^ylS!`J?|iiLSY#%+)C|QZE2szn z9Xa@!Z$N6PzVdK`8ZVM%sQFTz(3A&Rd_gAYEa#eE^GB=r0AE%#)WkBKAML5K*F{=S zL#=Hh+CT0+ z2a|8VRK7>cxG~C0t-f)%Ax<{MKu`{wl~)|txyJaJ54I3I&;`9OUJs(}j=iEs^#kSZ z&Hdo;fstXHVL{E@JXk2LC)_PeX4HkpD)3i=whQ+oKCniSD;pcxugUQIE{1+NpNszh zMWfZSl6!laM}Kv9R*az+4o*W8roxSURbe!?_}CJX(93SFC_?edWJCW%d|c{6mU<+1 zv3%@#geZ3(S|bPq?sT{V5MOB*V3-8*deQ)%XpIA)REuvpt%Z#tViGX@1^LKdMaf-U zg%dz^G|3q`u5Bu7D`1bQiFugTl9<=?;VKii2!x;1ecImc7AaJ9)G)FKgQbwJU%pQ? z9N(~d0t6`KGbxwgicSlbm^CLs44cXS7%fdbsIDqcR@f;AlU$YEIjs9R#PxhmoN(TU zOK^>|e}>dpOvs(#XmBN3^F-jl{ppY3$Fy~ClK*iqr(p761SG$uLbN6qAN?C%p8E9lb*~3;p z>Sx2I_RaNASb@-h$B5`QBBo)<5B=!SJ(=MVQ5i04yj?e`P}7pwHkM{B>Gxc8<&Zj9 zn}%azs(tR4`uAu~D|DQmAgC3}V#Y?ICIvH;Rw%56KO{|s43UZ=yOK%VqGIq^Le$}- z59!wKL`=(Cuf4K~kSVMq((f767L*pns)c;bZjMlqUqnTzQFEuUr5Zd9wSjV!Hp@W| zQZrZVxlnqT_}!yXR3{8HD?%AI+tFXD3Nu>4he;!CUNR!$!Z`mN^5Rn$K&%P6Qk!|{ z>i0QtUv{^(NeQ5omJb#i+jXRq=Rdha`F9y!2I7eCbbUQhuF4>zi~ z*T4bM+k~Pg-pgJ2g(}Ux=TX`D{dc$(b%yntjV4(mLzmhxK(zMBdG#2OxT+)b5Ez>+ zco(AIIoqE|h7Jl}rI&?$zM!y;iqQjvD0I6zq7{sE zPPyh9I)1!kTOV?cj?#4xGo<(>^riXrQJw0#FH0oB8iY}<3f6IRF=MXF>;lU*H6UD# zvS<`$59D%R>76t(bPDe$1D{)4cFI{-g{$HhVa~{;sn>0Xh9;i|d$hzVp?Qo$(2rQ_zz6n11)MXgDbCm?5U9R=yCT6XOH^ zBc%MjpKH{OII9_!JR>S57SeG_j4>)i6yC{Qxj#k^tj zUtoOTetx9Shtbc^(fIG67(Z6$N5krE^Y)q@^`8Ut_GWxOqJDm;M}0G{j(d8@UWy$p z_p#UMD0HEsD-}0E-}R`)|4Pd>A)bR)&J^QSXfJAHE&(}|4{O^Ta7SPAr{^qpv8g;& z%E%n$IQyozjc6sf&dp=|VCbrhUTS;-;t?>C#@@;dASZ?sqlp#O{45+7r3`$0+cTF6 z%P$w02{A@F8LiEK=7nVy%4M*u^>U(7AuQ)wNuV;?`t&3t#82c=f;OU09Xb9KGiwho zbwf%Ufn5wS5$Rf(2pJWH>=oPX3ajCocUX(}2oqIUULvzfGw&A#Fb*Mh%}b`^l2{mB zah8{Bc?gi8;PA#|>HaHX%g7?zpOkyEEuDoW%WB?juBk28g!d^`Mlsr6@1bHt#Sce_ z02u^CSTE&VU_4z8<#VH+yhz$zy`X$h;KrMA3)Zbbtvy;;-7B3~!(<1>xgwy^v}yHr zmZ1bFoW@&Dt+IG-8ifBh4q#JrnKw0e#o1b)D{l%?v3_2L{u56kgLl#64Z*O5+5Tre zREOp&-J_ZYxD`w+$r}5DuEGbi4*xSriUyQ+FT8MOQgDCFIH6~YOBTch)5yp8DbWec zylpcr^tBqRF}+R}gK9uPHM$1crb3zh8iiYRkQi(w1>w*boj#?vB;3De`?8rzz^esR zYrpx%mQ*p`Q(i`(;;x0)yLNg8>1{9}^pB{H_YLJ^)T?g0Yf*!?_EFVGHvtU`qsL(m z*BpUl2C>&|?mtbwJ+Ar}{2()eCMlnp!J;4jdsK!lWx+X4vd!Lx68DNm_NXl6>By!R z&#dZnjjgx-jtHFeML_VTHA~5`aCC^w5q6SKLmK}-5z2STAa?n?r;0nqi+EJ?ohbHI_P$3FVJcoAzl`f>^UFPB1 z25+e4jl5;ZJ0eeTeCqx;)94Qx5Ga@)S65nHNz^CO*}4)5Q-Cfo_R&x649> zD?5ViImm41-(oc?*)|!Ph-nARO^23*G8U-I2;OnM1V}Tek_%r@WQ2qS>O)_0ebh!X zn13ivE!E(4f)0bI%}EaSNr?gV>Uyp;CXr|;$Ztmor%|Uoz%s9NlC4&EnWpb83H_;{}jZKfn%O(YHD^ntIXC5H&+z18Jc;3+!p^9q%+Ce zf2IL+8_>Xyd$#%K_KHR7@nw{j^r{J1*H3k@Pb3Xwi39-Bav43K+i4Q`z0HV098bMz=a0;vIC zp@q%!qZ~7r3FxiK`+6tF>mKTjp4)$^8C}#0>t%{CIxWB$BODGDi=T?TbflA$p% zzuAdCsEjPH5_*P)jCj&Umge>^KS%A*qbwV|9}!LpHe(z%`HyuL{{ee1_i=iAz6B`1 z0R_3LJ`Z&g5~$@E@1tGEVX#)UcYt(n`pv3O6IoTnmirXyv8~_@MS-}gN)?>Vm{z+V zsGFy47Ka9!kc~BrfpM4qvE-vz9ILVWOPlc}TM}A$dZ^BMTX-pHsNWNi@rTk8D4od? zm@JDpq5UFfML#I2R^76WaIy)^)e6@5jDU=O6k> zJ|V$EmPwsf3A=wh$l&fRb@DbxSw&}+5u;o^9C*Oe{BXUVl_6+Zn5?;cd;`Qcg7gdz zIj(DJ2Jh-m7n(Z_r{RF8=RvF95&^FTnOjcUr`Pk2oqA~4Yx zDBBFnYfCzHO$BSu-5d}%@s3L+AXDwH`R&{irPQ>=mnMtBRRJZ>|4pC=N}baJSD2FL zrv^eLrhyv(gnf!XgmFhCrQ-bf*T`)!_rfWnc_B0Ql1dTYRVsxZ<^>a*aY{n}5GK+m zGLU5v&&Gc$1wGp4b5BletUif6*KzDHa@?n?$@BGcHo>Ym2KNB6AHts5J5YYqm}445 zylB~pK4f8*ebTgqAc85nWLXvpv4OX=8(cGcL<%MI*$%~Vsnp4R(I0i%9!*y_sFd`O zqpE7wr$7pwlOGv>Q4=aX0nKgH7T!vg1?yiuh_$2~EI_-&V-0%t4`hh^ArmG}8|V9` zegHLW5kj}pEAJkv$JnZ1sOO5UtWFKc@!cD72njJTeWf!8pL8y99><8Qe20tH1H^1C zkz8IyIbMrq(t^+k;ErpKUrPh$?KZx^;AOA=(H@i);b`PXoxZ{oh}ccz3Zq(3oN-{8 zL+cz$xOs32u-Ce;4MKa(T(>lqNJ{{Vyg(R{s}oSAR%odDO)1uq4=eyXa5wu)q`}1Q zg|PLg`%ixxqphHZ_mc95ShHR};z+of#@KFCX+k?BhC*y&NeB96z>t)VmUm)AID;#; zAy3Vgv)4F*xAx7U$n#lv#1LQNvW=?$KnNo9eRX5#I$z$6n3LT-=yP-VkpiDhZa>F1Lkl>qqyt zOEh2zO21g<^az{i4N7yxl9TTV-Z`)>;F+(5>^plj9gyeZHTlmrgBtZV zsn?%Hp;>ReF@)t3FPDM9M_);}oQPHK7(RE=;b%Ee>Fz|4rU~_3K4({qzMuqOaC&jg z7=n#Y=-omH>1evEQ|^Br=a&wgzcFGodNf0U$N3&`Y6*VFZ~ zYcc-@lk;mWwUikI3r}p9!zdz?5nw)btMhui(Eo6PZP&ao)Q1z{E!o?G4VGh=0YK&8 zZWc^LSL@J0DPANn{23zoKGoKl#%cnL+oJh z7w@mxwn(+-UB$Q-vBsPokF|BxL+l|>#Z`5f)T3fpVqro5fB#(`zPSL6bk)r8w1<%n z%L<;=z(xUkTswK%94jiRGVqb>BYxYfmu@Mykez$biq5bYXH?<;!dj!|xC4)uMIgbNp8wOOyEU*yQQ`MfV{&Q$yHMzhoSF2=jq~i7)upI zG`5|}c#&kBZ(+kYlEY)jj?1^DAa7vLZ7I;TwlX3`#b3=ZukY*p#8^q=Y^5qqxGLQ? zyi0Ux(x|AAf#EeoXOy9@ z7StV5wh?!6y_Vv75|(4H#;!hIKh{}I^!E7U!*;dT!C+)H>jXI*roh-0UzI9D?QjFg z1~-W)qg;DNTj0Uti9bb2Hb^cLJW=&KXBX{Nh>P&+$IVtc&qhe=e8WWeBjB28nCXc_ z-S$$R^VB%*q4p^)tPv{D;?E`*32c>=)I4uxrRkf?ZS;MlWaGmlA(yAP%!rfiZSY2S zzVwbIVWrvk!sVzwzfyDkF~%W(-yd|e!G;G4Gsk6TKFU<8&PTwf%kTkZh7d;>1;+%} z6m&fW+r!CrAusZSGEItijZni`)AB{okMITr*#X9LTEi9MVIID50mj>6s}s83gvBGh z-&M?N?yQEk7PwMCie5W;+DRc?)m-Vog^HmNmMfjmN&zk_d!b>hd|xxnrN>As_);~f zC*x}aO(E!2*cI^wj9#*7VWOZb4kp6~!W6|$u@2i1tH1x={Z@QzPE z>VbgT5|2MYf7+}Sed;< z{dc?pHKO`TV>C${i_S;Xjg7nneKuT}g)N$sJ;Jn+Q!4Y{j6Rpw5{#mVjW&vP)(0ME2<{?=bHkO(YUM$1R z44^>~_NzHjC@qhw$f?ulnP$LcspmmZYG~evqFX3&b*tMIRJ*Gw)6z;F zdVfW(^XWcp9X+*KaIFoTuq@E4a!{+HId+C&H7J-N2*Os}igQpHOXNVTC z$B%Y$wgD1D9HNdlHM1os%pHPoo4ChWZ&9wSbNWapTo|JhIo|~Cw#Cm0k(|~ra-0Nu z@4ClIT~(-{th!5J4DQUHi)w#vCL$CUZVkQ6Kp9f@L=5A#=ue_aD7R`#XY7Xqzs3e_ z>xfvV+k(_-M=lne@w*Enrnj?y7ZEZYj~seImD!B zM3NyIqYI_Digl7pjW7U5dh?Xej~54;$;7uOIZnBAd>|0{8WW_nxh5uy`<%k4H)hkl z_#+4e)pfjJkU;S#DE-#>2(mT?JTOR4?>Bx(w7L27d1&6E{TUgR}W+!Li)%& zv>-hrLF!P9Hpv8uHn^0kHI7;^Nr?^V?egScd-5XbI|S`c!t~`wifl+K8B{r=A)u}F zK3O7sXFE8z5%^I%46PH@NZa$xfRx#@P~Y!a6mrW(Tnjo$RFW%bjc zpUY*XUQM&Bab=H2`IUo7kjAoUb*$nziSR1^^!y}6E$0QTr6!+KU2peW@d?GH2sC?S zT4fJxO&bbJDl0D39DZG{TcZn!huphyXI*Z|S_Bzy1GpXYI|M@2Mw6Q$vi<)7v!WIH zgV*R$P_o@;geqslN58B97NOO_zX<|B_~=B0+*%Hd*m%lD|f`yTS^iMlCl z(ttRPea3kU0WoQ(e##Av6+WcsxzSGMt(p>ZGY7FG>q;AtlV_(IL?=TW{u^N!QPb6D z(mvCAMbxo|_D`2hQvfoA%vqn>krF;Rn$p3{Z>hD^OtM1V#^YYM*IP6us*k97vgR3! zyE(l)hsBt)C&yoA4q2aX3)dUdu3d0^qw|dZi0LYYUj#pWr%mwh(oipZ?oB_o;k1`7 zX)wLHc>RRa$g33kMExm;Xrv@6Mo0M=Pw1p$wjt6r38eN-NDFjI;e+tpftu~bg& zS=U>FfiV`P#`xcEI@>`&ul)WYlOWf(uS~%0HK9rmtjjj0Bl@&j{mdu;{Tk|%9r1RMB5t1?jxsdH+P|1HNE_(OdN}C&ky!Jds zek`^%mJswJ2$^BVLUPcn;^%eK@tc{uC|9KpZc%u82?06s3YndpT_Jd-lj=5k?XlQx zy6$#n&h4v70TFT=Q)pVg4j{%U$Bok?aQ%8S>Kb6M49Kq<2WUgmYNEV8AWoPXc^#xJ zl94}@a4mxm$FFMi?+RXA{dyBda@FbiqMy+L`^i^otpEH*dfYq99t z>XGzB!TXE(5CORw;{uL;QEvE{zdP>PDa&{|2dD=FuSI#hrG?enI4@Z8ndTk;4qY=G zk;&O>&d_|M4C}VMhTsaGhA1}?X-HqJZ*H;r>}6x*><9MJSA50XnPG}-jr`w6(b~S8 z8Om0MRb7C?N&1$49Tr;ZW2DnXPz3*Ep31b5A z^~oEd^=9IAL-qV^WOfQYtHdyl{^xO-o>3B;EfJD3G&g~e!Eqcqb1PSc)a@BM@DGdX z`{#MZ82FLIH#^o}lQRObykRuaL%|}yH%?5zOCn*2%Ka(B*qtMwG9aGN%ol^g@P&|@ z0WxY8V;n~V2_h?XL|dDsc|292*Z`HoLBu{bx_jzf@=&Tj@=g_>N%E{YE6@|uJjv(s zP6Dd-OMPKo)nsS3$hEQrBcotY@5f17be$nmnV-LXxgc?H*oWHOCm1Gr>*KCp-Ku5+ zQ7hyMvv*l8moEGEc@QG`$HvNf%v8p;mI#8r#~h%whas^fzn7)kXts|XoO&v_DeB~N z6`an%#9VS4&lfQgMFURGdlV+0ZtTYaA8fOdcZW4n2J8S~o=xzH61jJ;rrTAko0!G{ zXQMfW?%&oRpgJCM^wxjC=Jc1SUisc&gFX`pg`5Cckpt8?_i<&($drx-l+r3@6WjKG z0fOiKfr3jSB|BanciUj=JBb9S>q&xLx7M$ z;fC+F=tr~2D}Yy5AILcYScz34J}-oS?A%_w-#wO6`{$DX484T%Hl7=3qSudVXrB#} zc&Hh4)BtA@nR!0fzzs6=JS$q&3rM&O>m%32)GQ7&+MBiChZboXx-P?|6alQ)KeZ09 zf89@HD>IwBKi28;#{t2TUW>mFoEYbFw@(7y!Fx6 zauqEj=z6zhJvg)XHc))iPhVwd?O$+Ma7~qrOfGY;t%dBqh7G(6`6f|L>DLzfp^|Sc zvS^S}mM)t4d!~({2_f%?#W&|0R>3BKf7Ne2J&2Pj35FH#Z!dSQmWWtLVr?A^?Fxi@P0gw+{{m2%3ra1Z{u=md4 zM!A(?#4?ckpjY>d9y|D5qRX)E9%;s(6j=JBsXU-aP%8L+UrvjY&Hg0e6PIC&Mmwzt zY{s^%j@w||kV(U#1bcw#2`62YAf91E2!c|2!fp7vvXN7C4mSTqq+eyMuDFh6^R-T; z7F(>XI8}<4GV&o7>o)oJU@}Nhvkn3Fv}|}+C}@Ty1E{>L6qo#V%>(W{3g@)UvgW~vwP0S;v03hn+8Dqc-br3$ zrcJ*z!lrB_g2cmJ2krx_M@GtlEH{nSQo$4NHT{O4%PjMT>OJ^%Uh!;Q>XW_xP@?0F zKi`QI32++J71FSs~zq<(u=OGZAH%iUQfPQJpV|M=c|Z2dh|3WK~n^p1|AEyn@AL_R0yLHX>{Bnt@Q$wqxK#DP8xIO$sIYBBuKC9d4;lf)Zd1-7IpP&_>@z&(K{tR z`)X9jAW{C4y@5{oN!ngLB!Ko~5{B&T6_=0Y9h8Nnnoov-(1M5kW-r}nMLTSR@6473 z-Luq(o=kE;%kt0|kBXGwj%Csri*nvzJij4SSeAF(5+MWi*KzzXHpb9)==}JS9W;5Y z>1F%868Ke{z1B_ez&_&^wSS3(l|H8RF{dmj+=da_5}he79U^}@+B9i;MBOZ&JpSJ9 zzVM?z#6c!8PaB@xW0434DB$`GqN{(Zrwz`|0axNrZ=&yM+HVKMYh7{|F+9Ae@6^eW zg?eDVPf1D)gfaCk=n&>>3mwfEsjDtxuFlyQ^q62YHOcMO44v*5W`ZUomK>>#~;_5flALVMj z8r6Zn>8gF944RWQmq|tcV~0qRT_IICyoMZswZ44cK_weJLb-W2@M`Vxfa1+NUY9`^ z3yUQ5CjP#HK3u;^Z>yY$CnNU}Tvo$a2T?Mk*q7Ixx<{P^Pu%kU{vGOE!gJC|T2=>= z_1HGjv%a6NS`Ijta6DmOhT?=lM7FQ+K8_eGSg9tpii-Bk^|2;+z6cqXKwM}WWk?zv zx`}&3M~dwT8Cs2b$x)jPjX)IYMYzQ28s-hj4>bL~lHobj2Zu>7Do)_q-LbrQF9)`X zW*~VI_7UVI6=F3s_hUxtOilDr#y-#IK}QoCHFIF{(J)~luwJ9 z7f+?ZE%_&ee1((2!@gP@k~E8yT>;1vcH}xth!jSwC|&~xOK}OR9p}X} zsXRz^F^&fYw*1kcblZW=*x31~PmZ6cLEmTi4&#a}rpJ9{^_NoJFy)234}4wItE{lF zf*ps!f&WTFGEBTCp_kq>w4c3Y!o(;EJ>5Ee`Uej#3G<%!FC2fxs!mX;!-~=JNE{)= z8-*(za0hy=FNA@izgr}vfl%XT5a?0T*+%zet}g6BBfJtbiQDHQf6^3%Y~@I@6qi={ zNsc3#6@E0EG!c-7V>43e^yjzsX8sAV#Q-2^Aq*F+{mjUM>9oHCUs*+5lQ=&hc6Hj) zh^LMvUKh>1a5Ki{-d~t~+g#-)9^B&M93f2Ou4JFxQsMAeE{erx!Kha}Fb>T*Mz`C^ zv-eyxmEl2yNL|k?i~{-*7nY0|5@%+-{{93=sZYm3kD-X}q_fXH%Hv_XE1Kpa*K}uf z*)R_I%TsJj%W`oNoK)xXS2-Xl-7)dra>AXYlH5AiOX}`3!%@4GBXodp=|&A*6Nv|_ zFLGg7J(iE^b>S5i3Fx2RX=^}u7mj1xqVAUOM-`{krxdiIs%#qB2UK4V=AZ}L0x(q+ zr+$XQV=uu@3sr+RsQ+fbxn++rjPb6|`bWH{rXnE#?7rky&7`v8c_D^u=C-0hL~xow zqyU#ws2G+0$?gpsWMnC=7)MKyzq7Xn@%qAoXCMvKxi${VK}Fht={JsvqGHojAQnP^ zxkW`7IQK}jW`~t@3Z>gJz9ZtuHWm}}AA%TIHYI5m*8H6^W!6kNz?qj4oabMzRZesD zwKcv?B__m*pXgKIZX;loQ3Ha(cIh^$%RoGfc$J=&?DX3YhV%)7;F0_^kyxu|qe4XJ z$hS#ZRH>lSqMT;)<9{B((iSESB% zd8kP3k1hVG-0%Il=DK z1bUnP3h8>_JA#=_y^q8fZo5%2w$18TPLEd>^4H`_s03C7M53yrfz#%@II0DYWKK#s zD^a)X6W_tNj-n+?DG zorae3`+PK`_iFXvNl0_kHClh`pxj&>TV5#p$suSBb`z&u^M}Y_cS_EP@Y~TMrq`R# zdM23c^Vqwu>;juq*-a_)kiS$)hJa{8Ee>~T0C|5QtdzI2{sOOzU!ofA$!s!92<&uS z09((WrqzAa@{ao=)_~~3XynCjB=a^~Q7{KS+6{WDd<*g134&N)X zb&K~ZX_NtUV4X!ZWkQNcRihPylOxffD8IaTDcjqXiM=7ff0g>Phg5X z1W3{ZJ9x<57UlR0UxBUo3;!9OFSMTfOFx01@GZyi7QWH{a2meS0IrUKsF1T1RQSmT z9)10bh~mdx;&N8ZXeQa_ktvT5KdE`4M>YISCQUc}$?2cNO#^#MW(GRBNv$Clo!k^W zPFE0wUu2sz0U95Q_)r-F!f=Y7QPrx&_}4+ooB^$Wn}M15n8#FGaV8mJF6Wc6m-@rt z5n~QYhaR!fo%}!58RQ|fLJ7aq04o8!3C3vql+hHkLM$P}mrcL^s!X_a39{A`buiy8 zeBnQ3>B@B@nMOcwDQ*T}0t!AS!Y86&0Zp2*`Xzt$*LQOMhe{O?cKW2Yc-(Obs-&VwB^XSjjvV8ir(tTRX`m`JMY3%y1 zPvM}vU$%>ZdXFDJO}~XlK7OfBpSF?n_U=A@vgr9NvGR3mkDsM6^Yr`n)f4B~(D^hs z@Tov5h~z3c(ztyxMkyiWf}t_+9lpqJfekVos#6V^LWYW@d#NqNY?>@okG2MCF#?`; zk*a60nz~LAz-NHIg#kX}h|}UkZO6u)!?cINen`2+@#kB{WUY!>#>;YOY7VC!RS$GD z(L-7#_B{+!^S5= zR1zm&U35y_bzoV&ta=K#NC{0{H&c4 zzk4J^hwyjks96im>FIE}9rU+Lw>g5Ia^gGa&G3WgL}B|rM3zRF`XNiSZM*7(5Q!k6 z1&jn7hs_cxJ0>8`TWyH6%zx?o8f?~^rqaz+yxALKUL#qiH?%d|BKM56i7_BnB(sWA z@PPF$?JGk7*rQt&v)yp}*=>T;*IxG(=d0Wmrlhc-FIGw);Q+;N;q(Kx1DdqoU^ulx zPch;2I5-R#kb9dk(jv*FhOx*l7~T$u5^|*yh6iMzGr1DIt;fujsF|}zvt?>zptHE( z9WMzrN$FTvNV8%5b#26`9{+D;S{Z1cWdo=@_Tf1eIldQy^^S9oYkFh1793UZZuokM zOC?IZT5OB<=0Y0=Ek>&S%SzF8*79ABA4ykgeRA0Xh<%105P-V!0RH@pKE=&?yYx(n zBzX^(OuFdv!JGXBD#dTER zfAuMgG2lFm44={6h9-n8GC3==ziEiZA$Xt-D~PKF#2;;@H7>4A9&x-jN+=Va80m?3ryka=+}Ng67_3Q zCYwH-0K1dah5Fc2*$5hX$-4|UEFN009SY@+rz z3WzoKU%3l&Io|DPuBvW<-x^FNUOfv#{t>i=6?Cwvd{ui|nAZW5ck=eI6+IW?!v|0l zaC7oQz+QerLICjt|4&^qdBkY#O+_})_7I-6$lV-Vje%ek1EB^|zc$$=A;bY&`;yR6 zqTMqDqGGFN-AaEXY#uQo-S27%cZMZZ%DfCiNHg{7u>D6a+rv^pk6JlwdF@XSB)CXT z*CDhQwlS&w5>mVnvt4|zY7~b7{BTS47ct|esHYw!?U2J>y>iL3aV82C$Tmlpvq1luwdpj;1=#EL$yHtzY8=(u(OS;MmxiAd{z>&`vgutb;KcadIln0f zX?J0d+pPn{-2GkJFrX;6;9Sy?CTq~8DY`c)vz2DF8|t}FRC8>QGsxIk35P5e!2)hV zss)(9Ka#|yk&7ue(qT`>n2#(%^r?0pIt0-Gy(iuo4W0mmoF0=d0Y^u{?9eEJvAMgc zdarK>XK>dbl8tO!_#tWrS)f!pBL;VP_+;jMVQP{oR`0Vq%kE-43GTAcr4&D>J3?{P!isAC+%c5>oda5^R3Q%z&qpQoRL zBI~#6<2jKH1OpPWDL1RQ=-yp%_t6%K4B|M)Bcc0)9vRvh2^z}PW2qjOr1+3;gkv=z z`AJZ>wgvU9ZuFWJpq;xN{=d0VfIZ(rtRu;=p2%i$wj0uj$5^KZ8ee-AIjuZ^AB}K> znUsVfNL;vk8y6=gr%hoobzQocBr71~H%(TOskHN&pjemFGw$L^Si`qIAPF?1^}40w z=K;?icNCCe?(kqNy#`YCn9g$j8`rRA@=pqAF0u)yvTh%j*{0F)vadpfr|&~wMy4(! zi0{W6FbGDgLMo1#GNVPDnCMsGJg<6S^Eyh~FmwPnsT)U`$}lGE%AQ_(F^UmUaC5yN z&Xce3xF!pBb$P=N7Acy6`Et>mGy3P2UN-*>g_jU(+s_X2Xxc{aq0Lp;J2_fo^&FY^ ztMRzSA%!JRwUiuy=9dzyGWdFW=y=~nWR)pun+1knySU`{pS+dPIOSI^9ePl(zVF)c zwI`z;x&1M-vMUfVIdvF4B|)r zF!LOlBmnXc097o0|6DgrdX>J(nEMHBg=r@x%G3DQeeHz}uTH|LbLe=VS_D46(id1v zzW$|(REmN!6#3$mTx_o^uyYUa8zn55^4v8Oz(=&3A4xsbQUR9LGcdbT|;b7ew*B z6;G^C%@Qgwt${)7tR>B#1HiW;`Z_Vir~@IzsHhtEnbw;L8Pu`NooCZmH-0gm=$}JX zk-Hna+A?Vd7&ku?qESsp_~Ew!FQ;D&rp!+Cv?3-aE28fU$UgGbH@px!%GQB8$^at!>lJ*)? zn&`L(vbbFgHEf;juKbHvxM5lN?r^91@XnvFMiz7E5kx=u(Jy)sKMzmnS&{qK8iIVU zIhk1`*jz`2&b&J_m!)7ka#}ZQk#lOv6aC9@WbU9L@U9uago?dFa5U~&U+NMm7weJyts=dTMD?YPy>ZGLduTI+^xf_rn9Iv&{ zE0yYUBIZuD6iJ`QWeTpDNCSL(1YQ=HyabPMc?a$b+A9Z#bVeZg;g7pi3ySe?=1nK5 z!-jXznRz5yA+ugy9Go~3=#Bmf+<~_S1>f+SwQ2{)#W5Vu0@ZM9U4QaeRn?Y+d7XuU z&g_d(^p?r{aF2(M_5d+**3OYb*o6A72`Cx=C+50Jr^jU>?y{8fkb2Qxl@>hF0Qe0E zm9G{_)u;b@6{z9SYpmN-urdzuigMuUcjKzGt$e;mjmphy`qQU?Kv-LM2We?e6i$2% z`!ipK0Zn@*9dFG9Z^I@yHpqhT4p9#TGyr-&oE_=>+sxAVa-W!M=5zjC%Jw2~@)cgh z06P0cA78MatqraVAHdkfw?WGJ^^LLf(VT?JP$k>1>5gZWEO~rl(;=+mBg-mEy*m|; zE`R?siyZK5TFlZ+zR{bEtjxKNuIQB;6vMULW&^K9S!ds}VwRkXFU;x*RF;WZD0l8b zW*>@q45M45jLdU;wfzccma6WSQ_B~iPc9y48#DN9;44K z_pn6PQd~*xLFKyXd`uK&lIi%7MM?x(mFlHpZ-6V;+GwjYN!Ulya-Gz;fMbO=r1^l# zbanE+(J(X&h=H|}GuL6yPBwO3mv{EwC1?-*U0zPX4>Ixi1MrxW@!L|9lqN*JOal^*SAv3BTgx~k z^x|@8;Xl6`rFsI#!rxz>V@f&oXo6Pj^e=yP~<#MmJgESXg=yFsaW2+NerH3fVH&_Aee5> zsDwOBS8*Wa&~(X6XcV~A?$htWa^8Kc9CFd67zrVkZ~jfmmtc77rX<>SUi0dy!eD1I z=SIk;E+rRQVN*SY*oJe9EGxveIx}htt^&FQ2#yN^w}{d4mDJoBgnyot&58)$=(c>C zm2~JRL9Q(_KfE}b+S~pY53{_U3_iQmE@%#8CJ-Hz1G!V#0HX%ObF3>9@ZOpiWDFp8 z??PDG|7^xlpRiy`rJTmGLbuA-3_NYWXyY$D?XZ2~nu`&$L?n1&(}K+~OjRDt#wPfM zzO?L9py%4aU|H>y)R=-+dh@3da~7lvUcb@xa6S76nTY&Z>#Bv~$o!3tuX0Tsm)^I7 z=RxoTM6aIB1Ffo+Cu6mY?QLm8r9l&IdsQF#9)uJsKh^9MPr15ct4zmbq(|2pZC2e- zF+l$6AO)m#7hzNzJdnL9jpNhoq^drg5m*!m=fP)>+qSRpiz&_fIxeK+`nBzbQ(PBj zIx~O$5((J@0>PeG$9$G~q4x){SPAy{1wyK^`VoA#3g-6=djJje_8!~82u+}zYNd^E z7LD+Bm+pr(H;zRL``*lQ<9Iba!xFsw$e$H6`l`6?Tr~kNX-)DhUki-SZmY-?EngOP z*7Qq}d5{%V_c5cQMA8b4=5a zxj&IE-3g^U?Zqn;S4;$JyZGl^n@}t(-$l# zwgUNpLbm~PFw7d7;B*=`7@W#(ON4}9o&SITfBGZXsyBK#oMk3s=IM&hQQpl_AqmP# zf5^oBkLf9dy_AKwG8*k2bGg=vaqun_OSq%v+~E-nxPpKkZ!gqo_2(NmjtVQ@N+T_q$a@~5 zI_!tOxu~O~6tD5wD{OhH7E0(H7=&k`#(2W+jA{fm#*rH zv2{ZpYi1Qfb^>j_u3re6yN1v)9OgNQ^djAO7r|+=wf{N?NqwPtkY6I-Bh`^vNYxI> z_O9V6UyK$vN$ITYus=7JV#aoWfYg!<4`y0r(ef_mS5TqZ;AdWZfB%2~e&DDhr1v}0 z8sQ-dxs4;LAfrz)%IeL)^g%1p5-@$}3cBQWy&Do0&fu4}x1E4NmDzJib1O|g45vS) zZVCG&iJ>3^5tk^SmM)0CdV6USno)_o+Rk_zWbcta@s8}})J{HOC4We)*W%bMvDbr!KsHP~Uvo~8wc-`26O93?r(@`H;z=wr(BjLW7Q^RzG7oQY`h zg7sC!8km%V6@UMK|9}5dO64UX>Uq(F;)XAt4mA&i-pkyvq7kTs>StJ_?`?Wp;&1yI zvHNs^Pg-a|#|S(|9&DWFSx>p01Kg}}%A9YY>)Sc5WxEzS&{~eCxl9G-@#+FYQE}1Uf?94y^E7&jVqRwYdBBWvB zk$xDse0y^OfEx5a@He0VFzS~P=l?k8YBJhf`Rb>|b^}pl9JP!^SRIG$ZlVG#D_Q31 zayLh$Rlw}y1?tAFTUopE;jz!*UVm?!cX=Ww_>y+tLwYA=Yh=||d$ORO0zXi;rZz;% z%b$*udh;j#Q2r7KF+PVP@Qv86{{h6xAi2?C7OGTlO^HEG`>_vP;5i51^<7-n^PA@l zr4veF!Kfn6%e$iEW=ayYRtaPb(MJZw4MYcb*;-MCZy!#yDoPftM?5A1Kn7%uImp2% z>!je}7xpE zRk8~dDvQgN44{e~GQa5m2Cq=Xd)gj{HRq`lI&o^~HYr~6?UBf)Qwh`p7o)&2{smja z&m+1{)FlzqSL`P%h79Lf0&~OiCRH5hURsecy3RFd*Vz_~JA7ng@F|b>0 zE7DcGuKQ6c$$`{Ig#OT&N>CMB)*{IribfgdNp(0EQfmmo+Ux5`rqoHngrX=MgQ$E~ z>~u*uk)ZP+>M$U%r7r%_m?-9rL11IE1?6qYtY{;~Xc(In?T(Qf+Lk=}1)+95k{LB! zzS*}Ubeo34D3HVyGch!zQ{D!1-4VOsgGeqW4|yr%9^`L+;WhQS_;T0qEs(fiJJ*3} zh?-_ZI$v(%1&84?-g`96bLv6&2{aEU3jHg#XoF=xT&jcRsdT^m2ny>x*-HuIJ+W1! zF@%U_RK2yIx4OReNudg>y{Z}gG5EE}9ODYed;P8kE-W?u@Y}Nq5QmAmmM3R*&4Y61KIVrtE2K_ zNr<&^cR5nllxp1Z1=9Z>d>e7>KAFTC*jIs}gx`0^#$b405DEyOitk2(lgf6!njV~V*up3qi#e$wtczly6F+4jkh z=>`KG7++F2CVz7MHu&s9v5EtD_J>yX@uc;ZxKjYT9REo+#C@qASw!~*qgg+f1JhSa zP8KL4Q*YpFx8}nM@-fsaYbIm2L8z@vIP9eDp8z4|fw>2$sXDdb&FXP?ZXwHbjf`RF zzO@ar{|9gRLm)G9v6ZXA$wOnosHM*)@c14>i-kJ}+5XRwr$v#R9h>{Fdn!U|bC9P} z4-QKJ;ejta3z>BWGQXl8Y~LGVIflhPb@lP5$$M`CinAOnmn9J~iW4tSOV>j8E8sAN z-5i@mD5#iB45~YS&5Q&Z@2{GFEoq4%=sg}3ak*UyWdAXfkC|d;!OfD^ecl+335dcxWXd6WyiuP*Wr#?dk9Ij|bGPH(-Z4krD@KJds{t*J%cMFTvU|w;tR_+c#2Q z52WZLGtNPYq=d0mzSg<uU8wXq2V6}k){QpUMg-bd}ap5IXV_{G65QHZbb4d)WN}mP{xP@?(_V5Y$GG!dNHtrj>z_eUU3VA++wl3+w3O6 z9tZlrO6pUM|32>%%*bIO`6lGCC}^e0&JtG0umxnXG(sfv<9h9!U6fzc#1|N&_?Afmt@qE z0+Q5mn|3$Mc;0R9ZBeZiorYa)!zuo>`%AW#f%L z{yRz>z~^smco_4BX8OUl4^)+&M6g!)P3|dm>Vl`(&#(A|EH1jAD7&qu$_PlNens~o zOm^Ucc4zaC?o}B=PhN0%@P1eX`X}xq^BYVk;o)1-1ivG0-Nc6!3fdi~6VPb(Sk`J~ zjhxpj709KKdF$_rRZ|{L*3n@RAXLA#}mVriNd*ppw zEVnYIn8Gjc~BOZi%XHfdbp^e=TEd4Fy*NPQ#dWP%kjuPWs z_-g|NB$+h8-l5!_Zf^N!;;Eh#={;06X?hDuq2kb_(4z!6Q$|Czv8;NE6`V_X%Wwx= zF4kVN-~t3jF2v*kPeV)yl>tsPxaMQ#5btz-D!OGuNPsLWb-DThh$N6YqH3=hq8e65 zMlb&7m?@78pC}fknrJs@X`8zLaO^&}REAg8qJs?BzgW2(h(2id-_W_;2rfEqdg2rX zZ_5-K6nhx(Czz^X->1Mq><$jp1JRyOA~7(9KRTpsFi^LRl_b145-diQ{5?5@d9s(B z>&|uLul0R_(B+d22U8w7Kv^&bO{nyv+>jt2X@n;SBhcziD>?Xuwehy>hsSfSd4nn9 zlzJ?oyFdz7u%h$VJ1T7tA@+iBtS*hQl)q*6MD1UR&tEm~Q0cYCJ24Z#QO}*&h zSQY@+HN{=$p*V=q{?jhdehHI3sJ3RE9duRczR(nAzB=}%Z0jS&chdRdPNZ^IzMxx} z2UGFms~Xfh_u!~|f**T7j#i!q_reH*jDIOb{pgP{!&;-xCpS`+Qi?)4Pq7}~gW<3c z&+xk0U&MEO7^}<9-V=%HdA!-nKB!h*-LiLB86=9B#|ik{J`#UN7O2Z=Y+A429E&bl zC3ee#Y?MRF;)!QYfhFZl)C`pXSuHV7Ug1q*@hYUL0MNcD4R@YyY}z+zgZq_wl}$7V zw0+pLnAn^iu!ABcjyd6@xp_YH+c?#Y5SK^zyZR_HNdf0X;9=3JH)f-IsnE#CVy@ld zmS~x?lEJ=~Mj~!OPsLa0VuPrTzv^6v8fs6_dN?X1#8C0W%-ce=sRbJ{{cT|d4JC?> zq=0ng$2j*BLOBy~4ai~6^U?*iH~={VY}9E_Q>f*%JktW{^)A=HwL>y-Tu$o4KNYsV z)h>Qq`MDpe9=vvX6Q;2gNtAke@p#upj8?`vUkyAxcg8>BMWPW};aiV2X~$T#1wg(Q z%Z8uB0P)?3n_8Wt(Xv3jmNnd^HFu?`U^k4Tp&dvsB$#ZaIeGCez`!_|yPyx9swACl zwR+hKu8kLqM~B}<&G#((T=wU@6h+20Xs20E|7y?R!%o+|&y=v^#_uposMpAo0uI`e z50GePFF;&H%UHSMe~Na4$%Dk4kc7PQ&I=vEPQ&E;*x)oSCHBC9_J9LTF305j7PDtCHqXq=Vr7{&^YOVIf0PH>J1fngG6r!e& z+tPd8_)wM6FE$c5nbS(ga7~l000000004mfu716O6=e|2Iq(V z)=Z;3AgZe2wv#SqkS=En33(g!`!Z1Ok;E&i1+sJ|rcK0D0*VzO!a=RH+<#UYsz#gU zLZz6<000000000002oLelkus$vWw012_SJ$N9w6pV}zFqxqy8C3naCrUKO*?2)7E2 zF>PNl*8*2#&sH&DZp?SQMN>?62^H5u0(q*%)M~4C#1yTVRDeAaOcCy>*PR3D>X2H|jeMou1-D z3GHe2e(XBy55=q6w}0fU@LJS`sS|7;jV5rIH@&br$d7(XfB+a?q`Bn&dGZFA{vSDO)tM1@tUvS_S`TZD^#xwh#uzZ4%k&(fixa4UOXarQyOVN88=h zW5HgcSaoT3SQHuvd~hu?bA2 zu-=~D8DU7h_>bILh2Pp3p2v?#|9ws^CgUDf6>uu6CQ`=bl|73?FLb13hoR@ITS!cD zx~`|Qmk6}&F3J=8;3*mF*C9=jhDv|{000000006&7BgS<&bzBlp*v99YeF z`)ygj`51@F^?D_C?N;QCZj?=twEo|`!)sC2hk6)QUR}MYvXWo>R%l|q5I9g)#4bg! z(U*C&P_)$?-%Dj_L$lBr4JnTZNBD3hoAeRo`gb`Gu5zIazTu~*3olAB9)sh>c3M)g zP4W`FX_77t)g@qggw^0A{?M{s>4QTho-5Fl%| zP@zxJ$tdgVupMvxBXoav;T-SfCu6(#5rCKYtI0?Yo0!`UYHjc(-xdH*mRroUHIs5F%4O$EzGoZ zO@;LQW6XX0I+MgCS2+JY6FlM?>I=>|Ho!5#iLZ$+P)(PO_v~&XxuP-VuLmoKg>fVl zva^ez#k&L`y8Hc%kRZ_z_ByD{FQv)>thA3J4>2=it+bZhU}w~B^GIM%Y;g0868a1L z%ABu3ve|&JKl|F;ltUt27Nne~)Z$^I<>dv0Gsyt70T-0{Q!Sd|So4&g?;O?-*jE;? zzv>N2s$Ffcl0PiPb^6Wlj5}T5bk=euS^a5={c;Q^L^3v-#O?oei^nmXT=*MXoB33?U4dQ<`fi<@g%PPw9$;36hn>*u zx88|pa8u#PKUuRttv<=uWKqFR3Ap9MTd5MK1*cwZdN%G*wdpel&&Plt7T)uiy0}ir zc8qGa$5w$bgR@kqJ#5Wx!_nJ_fB{Bh>%mBvG&$E%*ZW5W8eg6w+JpFyLxR=gOE$l{ zOdz&?S#;Kd#gFAXvJHQrrECCyJ+DNx4$Z*asis|* zPD&N??Z@hjduQS15naKX3#V$1k77=ZL^VGpXH?yivm@YiZj%%{Uj=*kn*a(5``cn6w;5+1ZU8hCM}aRCSm2c z)YFxt)Hx;RlxdeP1xKfzTWp)36j|Wqz9ECF~fT{&HoZ)63d`WZ?c`!h8f## z$s{NO2?o0$^q(pfr|aGF6c>tC#Yu?v^6F+IAxjH!&nel)=lb&hoql&@X%oQgNt(a*!5}n~- zwqh5<1{+JyMAMf9tJ(1h&I!YxrGdKGj;&*bRLM(oygcXH_)9(sP_yNKsZN0_FC<;3q) z7GS~|)FT1mo0%>$j3n=otmq{-;oZI4TU9^pi`%EmEDWn4&?LuzX-T8iVpu_D^l+;O z*VHJ4*T-Z~otmBBap+imbeU>guEtFbR$t-UDKad=mv`vph{AN5?7 z3e;Nb`d#uPeHBd&fU-92=Fhzs84uyHs*$n#9=teOz)7VV0e`q)Lban@d@Ql!+KC@n z?TWu0E>lR~%A^K4$6l0Rn(N%@xwPfZOJ9DGW9yUflGTfdWv0CYE4$EznQl7Vhg()P zNbq{|H4z-{)A2|eD7Ar!Vz)~ipJo=IUyYdXpH{1m&Pp)Eu(}HmnEnKLA*O61TLXN5 zR!Q|*kQ$d!FvRgSXd($KrZk(NQ|L6&i!P!(*dV5NjU-TkT1h`PyB`i-o%U~?N@M}Y zO?>|(CRWYm`V8RnQ?JzLp_s_@^l@dSi2d}texiCM!*`dBMd$N7SslJHXr|a2m<5m4`?K>^M%dhc zrNETf_h0mJL{G6CylC8jIF*QUJh<{Aa#UoCUheK$n?>GiRFQ==oIr2y4zc8_;fgtl zx8L+7>^{+qonQq=NYu#OJ+7{uBlCYZ!o<@e*-G%peTEFF&&=G_HYt~75^hU=@zF6& zGnHed_r;&-^6B@<4;;T>ni_%Kinay$3?Q>hscCJbM285rvZ_Fj=0^lM;QuUy zG+*c0^^FL!@m5_%pFdh+kVDtWSdvdi{IM{nLaU1RNp=}f$z2N~imIpn}UtG~3O1EX*4K22+=E_)Yzj-KUlPlq$0UAf-aoxsE@X}48K zpil-yb)8-%JkU$T#Ky@K&U%N2X3EX?WO*mRt)rupH_j<$Wl;f`?>pjSjQ#oq_gOqO zAc^takdnP@PJ-YMm>bpvR5zw7y)&-2p7dI)$dL3|iFcY32^PZ4S@Fp2<0^THQ~AFA zIf9xI$UT)Q{EY06>Ek=lo_T^<BqWMq*@KRA1Jz)u{g zw@xbMCRRd8IN?oXCx$S1@Hq1~tqVu4 zQ!MI_)#FX42e`aO@BF<1%VN`hAFo3whmC!IVxt3f5>SaOVzz)7qMUNm1!$BM_3 zoPDaZyL&m=G7kwP1y}BRBm}M{e0h__Jl1|N`^Spj|1mDckI))ql6J}Vte2R8W<4fe zLnWheK|%dB-vrF>Ig20R!R=f6-R`*1c1`0(=0*DQ^GiVM(%)y>#+WB|92R}DQ2eiu zcbRP}-xt&<6(eSNM4wSjt(p4FmN(eVMez#Lh(j+0o64JR>naf}dhuTzrD1sOv7VAr z#;~)|>1R^=H0?fv?y`tYfrQ_30IfLz#0n{Lxn#)Qhv>MiCthT$3y(GZGW0N(Y@f{U z=K@)W7|&gOqD8xxpj^?>e5(7zd*ka1uQX-ZSJ}4Viq{++ax#eyw_3Yc9UCkUT({C^ zHcf&w1ZIKG&ZB`E&_D+;59v&QzJ+XL@P5f#j5~YEs6_GiQ5~ zRANG~OGe(O9XU&a1d8CoOVNuwv%5cddWh|D7F&s%F#AiKV&TCX%B0J|AE7%ciZ zB|povi1JChh{5}Mj_lEVvCB+8M#S1wO?%d=&8pdtWFJQ-#n6+!Wx}D*;|%M9DknL@ zeM>wez(Wt%=p{^nuEy`ozi|o@2Gp zh~68{<5T{JNp4P}5p6ggmOyVNOjg8uYAH0lPX%uT*yItn7Mu?6bo?YXnZ`;CXG~Vo z!dZ#xod_*eZ*I?XTeEIkxo9~r@DQq{cXt_iniXG7RjGb?bJcXJ6lb5%u8O2>+xw=v zDJl^(E{YLb+WxyEQ-S#tJVCgy_Hk+ou9%HM+SU?dB+sf*8ew4cw@YBVjFj!1EmE9t zW#`nPA?3*@*Nvf6g~}uItIL~AY550XM(O;Sl*}giM`Iar`j_mBnq^lNQn|9Ki`)^nEo0_KnD+Se-l@tG9*MFEG2_NF72q+I*Q3|AN6qphL2wHeKh zc5)k8lSQ7xyP4SxILnr^gY_>k*p-#f5UC$GmUpkP;ETbt&F&J&3A*?NLaJ}o$NwB7 zqrrYY_|YTaWz7Wo`SI@;41EE*TQNv#Wy=y6+nlj&8~3m^i<`7x)`L{iecyWHST<&O z#R7P!Z4KR*bu6>fuyOm}dl-f%)QI$X0B9pwog*?FNjKdOSYZBpk3y|Dv5eg3H&c-W zScBP2dnlQ9ELvX`F@z%ewL%OI<$&@?C^&;&5XZmCPz{){O%o)G1OdgfLgP`CBHwuM z{-!uC_a}N|@@UKF=pFO)s`z_W_n;cL=ont5r+T0A zY76A)g!p|(o$vYH?%$H{d_I6>-nF~kbGf<@bsX}wBSG(+O72~qGxJFc46H` z%Tn;_AO{|k6izY|c_s1kl_}dWxv)(OwMEeYd#8pD1~V|Ob%4T;)}T9FZ5FrE)KR*8 z6@?2=)Nvp7Di#%z+mZU;|1)6PLjYvCFP3H4$ZJP`ZI5lACr$1vH{7PlL3xJ%FN);K zMJw0O49puNQrm@!{F^qfWqA8Bu`SZQh~T25jJ9xTAk+n<1GSa$v&P`f-C4=Gn4^|n zKT!9nd-FpC(+YC|_eD&=6X>y>Q#89=KP~ypL3eOpTO#`);3Nr0S-W z?e82rPW8r3iJ7sUpRXs}8h>KR3cRFY86S08XTkeL$dtBXV4Qy~ID9JPoU)8)Sd8v_ z)R$^l?hTN7w^uLC1&w4K06j)NF z)~yRYHX>EwUYTP=X=TpCsf!uYX{#%&hyD37ff8ZC+aecLyt7XWY~GBz!$bR=5|Sov zSJy@2@oG$Avl1?*{6QFxiA=;@D?z(ZCXB|y&FIwBA=WRxP+k2R^US!B*UA)3LqA8E`QOh}Md%06~8`S&@&yr8>pacO*&sx>6t~0aV`{Uvy zU-I;xW{_ID3Tm*r+QXXg3M-Hzo;3=GV3Y{#7oB~k#sOK*XWfY!5i}w>DHiY;6+*bM zW*oqeK_(I2FXO)0F4aRkRRhVA!awjMJ-TY9c2A&F;Rju0bZ~^gmKHCmb*2A53TZ|! z=2@ZLKoLW4C|v+Xp|I!cWRbnw8>c0qv;|d_O)}>0nQ1MibWUSs32p_*{SR;u0?-c3VwZI*d5AeE;BBkwEf~f`^qNmMs!+AQ$5)Ck_J|NTm1~$8Bsq_@&h=H z`@|>a;8SJ|0Ab$u`^~y>D-G#bkTyn@+b5pvE->{{DEG;1gpph7cvV8E0}J1;k~myx zOk2qnf7((T+8173TeFPZ9kp zM`+KGWHHWQf>v|;CNns5U{JEf6v#TrFC~qW5Jh3%k?FQLL94De(TGZ%k1LI=BZg1e zD@SST?FGW-B-vinyKzncDx0X`m7`#Y1s7kxVf+4S@TaYfskb1t%pa^>TTqy&OOs{h zo>r$x+lYgZsVh~Bya$D&5Xc47>UBb*`3mJwzu`cUkE-RjSgsm0=K_zxZMHCyx=h9Z z?pd(KYBA>&sS;q!!SCv_Gs4&$8;zf|C4$G+8u_;FIe-S0oq7+_klSq1W*2c^^?Ca} zvikmwvU%i)H-?rp{N|m6z}Cb7;@1|v9SW!bMw*!ADvlAZ8Q}CaBJ?< z>fxzNw=Qk-uzRjg%G{e9PS)Q~@66M@fqs+`D&L$9WIZ0_>w`lpT>VEA3|7}eM5vD% zU~LG8U84c3S6LD~OSU4V?)71XPU%1VTv=O^3Q&G#Ynqj+-8yS+ctb|tdKt`RAb?8M zl~;$HWvh!<9h^iN>jaRGHyVsU;0hiS6}=d1y&h9@HDMIJIH*qTEl*By2_4YEOXe_0 zyWjcCKiOd%s`v#4=jJJ`wg4T^BbPi=$efF*?+q9v8X;}mXty{@Qv{nV4lCK^2tyg@ z<9Kwbxjdl@ZvluBlqqjMNsQjGY}{P${|1Ev9p_IfNMq*73|zzmNhvF`O_l%QzR&>4pCp#B&iXl(fY-R7YX0%?ud;AP3brj@(c$P#mo#?J0PK!&`G%WR& zU|`6#zYn9f(C29Mp~uZQ-WCyyQ`*kZ8GZ@bx(yy!L6_0^KUWT(#j85+GlpZYY`&tt z)iPdFG(7}56zzp4W#X`dE&Hvf8Kgu2y&R@DACmQRVw>UotDREmg(P}_HO{D zzg>NrnW=?viIYh>0k=byc!)86gU`Kx!vpE~=aQ-V2&*LBE12BlrZ--5#iR$b>ZW#- z;-S;=iAKBzmLV)3{hyjw8`#+BF6V>>qUh%NeHq?w$c#d8SxCFZf=P0A0@_E^Vqyd^ zca*&A8uN*3Ga^eH+VD9y1pQ|RNO?w8vFTOCz(m%l%apse;$s0V$D<8>YwPV zIUR6Hbl?;T*s#p>fuWXrkKw3D+qCJqK0vcM63t00OQyh}ffNDAG&aA(%PR`oIIGgw zE~R?Qkix6yT93{JVY!lKaXA(nw(>7bj@sIa$6>*|Ghh4HBNj6i)~)N$49Fj&>4UlKk z3K9YW;@@LJ2DZo1fdq43_)i*dUnXLVUrnz@C>sQ%scfk5Mxge_ci`8_?rdze4g1KM zh@S%y)1a}RD{;x@5D4J(L& zENEE9NwjmSC#_|JbGSBXiyv`Eh3Tn%Q(d>U_p(Rn8lFOU8KJ`40{a^@b5y1YZ>D3N zG#(A?rT)Voi5IF8q0-?WdovF@20#in&UcO)vL@Ky=vgqkNoO|R)3%EF3k>q3@%*kpSwE*{9#NrFiK#+64nPP^}$&aw3@54 zDOZal@MT4=x`+O+w9C81x$(mNBXqFs2v^~t6?{WYIUX=T>orEvt*Dek>a8Mp78CfAuk3^*+*vW=o>74h@)FU~+OksiG!c+3U0e!` zZH}|{w;*p@X0EQRFwEh2X{HXLmtoCcB&7SwdeX-;H11Xg_~v<;(m5b&0DjC!REk%F zTDNb0$$U`mC_QrIomz?$jeGFQca0jhsM*;Pq9)N|S$#|WCG=L(p6(EdIt}a07nytv z!bm@JFRH%rY~bI!dhI+2J(rGcz*D$~6*_Dhc5Zf{gKr?@iZ0=XD&O2}!<6J~*H3B@ z{5X5bEcjw;50n}gSVA^EXg3c`;W*L57dop(SFF8>kF=xG(omf2*pdj=nfQ)m%L<~B zg%_Z6|6ypenI2(}RyPuIse`_}_BW15@jN6K3gl!T{2a5ux5A(uDine>f(>xRV247c zUvZb`x>QG?2g9~{?1O?kwK9e!u!cW4CwLX1pvK_<>d5={fSHHv4ut5pvK2uDOZF|5a3rKLs`Z8j^P!N&P)aXTB9VAJ%miwyd=si zLny>g0HGf;h=0CqrmywXlt|h!0UKSlK{+7D=&5}H>g+|4a9fm-P$Y2g?%keDKOj!w zYv41fDMtR{ABSIZ8DRe{&E{Jq1Qmmsvd>C=eA3|F$R3G8yzU_USYs0HpN@LcjeskN z6+>2IIveM_JsE4;kE7G&$Q@^k(am3s(u6Ft;4(31VYRn3vZ`y*)b1Wgilk%YJ2{}| z7DN0baC3_26lULT@utAJkyF+T39VXlb$cC^gmlZ;-lYL)0q7Z@c5!36xX9XZceE0Q zxxvx=&ZnSJGrr&haQ7tp55!oA)$0@1wRX5%Yi*R} zOLLn0Ib$-vv%>iA{d|koL^gAiU7bh=f=f3?xa@84Y-ydoc0+#HXmPxUMf;NFq0;x1 zmR><~lxl{kTEGfi!0t}O{>=yHBNCryB;S_wWnUI; zs-X)T@`J+};klr*$NWC>ps&sTaHmFV!}*`(Iv}5>zgjmM??gc8 zUgkUpg=TwE=UsB=l!;wNC+Lbf6?H&=hVK$c@MvJGwE&OFyr>m~ zvyQ88kw=@qxDK$7+?$+JV8ayiPeW+ll^^u!{a6Fu_#`=o%D#Rfu9yO=*!iVlXMzl% zd~U0^ECbBg;Fpwg;8Qgzi?NGaGC7_D~48Ax%bCZ*j#IG8>}VK$?`qJSdgG=5N8(#-5X| zSg+qyCiw85J9-z#4kdXmt~F`mkV1nW7 zLs6X>3yn%G$s z4V6kt=f~2@AVXz#FiY(C^u@8b`lN+;78{;% zXi;vtX!T-BBtLTl)c*>D5Usm=5LZxAgouiB7_Q8&Oq)W-j(%XgsSPZp|9es4_!Jc@ z^ufPtAyQ@PJNTs!8{$rH&(2?dRPKacQq-mU>eRHR~B8aX^RDmHi`15*}F(35G^X0dwhPPDiFlzk5AYQL!t_TnfB9`E8mS^|9x z8iNr6xbK)BV)o%$g%@qe@hB>tMuXcrksOXhHY1Wmd0HP88GPoWMx_y$YoBR)PCOD~ zMvy(#0GCRB%g~5|w)MvN+P+o#%z&yhAn_OrLo2@kzl#lkh0Zn}`*w^tWEZ?=M+{o3 zx95)_BHg27G8NAt)0*}W(Z%$!5xkJ89wh%Qzc6L?0G8rpA1~UIsfdc&E)9tMEBF)c zA)=$$bV0R%8%l>C^ZHCwox?!?O8(#Q#v5Y(+h+LYLLGuDH=c^&Vm5mTE(Ct<%-ply ztmqYqi?h#dl`wN;gn^C7qdzadNCkEe;i1COAen)>+OPn1-7@abANhSFUE53wF(D}< z1dWnFDe&y^a`fe$XEzj$JHl+U7ge(s0|h(6kX%evIl!+XB6&L02kZh1Reu~W6U4>kEE`=s(5GneILNclF_oz)Hu@E|-_5wNMV4RmbbinHhihh&j z$q5K=L5N1xacB-JK0?E%V8b+JYqR52-oa|1;~}+A047wg)AcjZd@#Fe%|+o2d@o7= zd7sJZcoeQx-|jVOAnXp^3fz3yFzgWiDQv?ugv)atKTUZ$*5nDz9I zg<(MSqLH*K4AtoQ+(ibsE-sMW=9&{JEMlTYOVxGM52j|LP7WN`ZbS=(U)FgSB#g<) zhw4BA5;2%NGu8xJgr|vEe*9GUz$V@HiH}@*^}`b~?NdtnNf@Z~ z@Pa6$**G%I$Ea4N;vAl(zg$FvN_B@czEd5(73@XR<&s#rmU(A(1-Y2Q>I%gk!CALy zF|E1_!XsaeLLrjgHimFH0bk;9v2l&>djPZN8fvt4Qrd82e8#IJ^fmenwd{R+lbJ9ujt7xSzlmZvr47asy3 zKN?`>WIO%7+?fH^sUWJ4H{*+(PF@{qmgU6_2g{07@R0S;iL;&H9f~g$>Hh7f6n_*! zMDTp)M^PAX5D2yXh8HcbPkKo)s zJ7~u+Sqw)rcYTeu@wwTvHHJkH<^5Zcw-f^!{Gr}a9{ zh?wZA!%W0Sln=#>O_Ric`?+M{uF$a%Qc!b8?mI#+^3~<7gJkJ^Yr@hm($ay{R3kqu z<|auV$TkwQ-oS%=Zz#uc4uz|tkQovxmnx&Wb-(S0kj z8z(u47rVY6U)PnoeYgx4w7yKGW8Od$H&nI-k?W<2jBS3ZQNFsL|dMLZOnPc6V~FIRiX%^so4BN)1^8j*y_MV}B1fTW|mzB!8@ z{eX4OG{tc`e%zb_KB@pvy8fwwCj>BZF1*@Mvk#ME5U6kscS|LHgNqvuZO0LR?jf*h znz#Ah|AlttWnH=db87p#+y z5Jw~i4pNJDLME|jK9&TyWC0xtCVXhSQ!rx>AYHfgGL;lI9JXEDRLQ;^y9|AUfzMTT zVqt;urjJR+JN@U}fByxpqU&SFJoqhwM=RmBM=T}^Tt+t)^@ZCj6PUF4q75pKV!KJr zi5Dr0-hk`^oZKOG=Gawuv@BkCz^(W3=b;W2MW!slX8XTG2sifO?*tG&YqKKb?e^4hTslkigi?O9^ zj>nKuFBL{1>gc@(bPuPXtPJs#c*HTFq|pIJWrDgsN8UX>Q#*(fA=z zLzlzbnkSEsx{ADB=Ti;BakES>4S1p~Dd2BFWZjHYo|~1EOo?(V zi&A#ndBg+_X+bhlsX&8X+BBjCOSQDZquUV!ylQy)(ouI{sU8+qbiVO!W}x!wwX9=X zPccMKB@&SC3^T7ddo*;xVzm>XQ1~pPtRrr8dFw_FI+&x zt?apWD63=YHXUEOVWw_PM&r*B14d1gYhhY@1IQL-f+N^R5rE~#rCaNG7+k@Ik$cI^ z51NFYHQ^ABn_@_mN*`+S8qsPS8~zyaM!w7zd6d{+Cornj_{YGPwAsMPF9fa-BCahN zD@r7eXi{v6Y1x+r-LJ)ps5yN;HCXw7-{4U`N7lr)wwI92g=8hll?#!*dDk4n1TnQj z>=sabKBipE=sKA!DW(aAmO9-Um(RIggjJ4vaW|-L&gbLc5YDjEZp~+;38?n4ANC5@ z=Ek*%$>iWTu1DH9c@!Zjm$bAs1m{0aCZF6Cjvg5frHk6!?TEl@7yFXnvU2ZCr`Fyd zUVdkIAA+)G113@R;xtY9MUTCwzaU}VD1L+vpCWRN({w>3D8d@F#lPknkW?3$OBE6g z4cr?}pY|hp&WuA;{GLYrnq3%4*m`2 zc3xRB9*iZ|RuUtQNdqw}^GOu>w~RYX?2RB2&j z>|;i%Q)g%fl&=8d(~=pigIfOzikzZx@+vB<4x2GVjiTt9DG=pT(ZvJ(8BH57vcgYy zUTWwG6O5(mh0l*lo+*owb=rEGMN5dhdPCS)z4;0wxQEXD_ZKN>x4(np1F8~dLUc>1 z@Dq#TH!?Ooy4nL@F_>+@8S}q8$$>4B3yjErE=DRdeLw6I(%UyJQOI!O6n4+etIMiy zgd^;P47P{QV2^97XcSO+Itn97!AqjLGCFs zb1S!FU>y&Q^_g$b`%b8U-iD5odwxL?Uh4*$MB7>BUT26j^7zZB@BmNGRW`U1)uZjK zRa8>D&`V$?9L9}JdLFTM(1=xt#LbB$BjzX<(1`1J446-dqZ|U!Ax4ZTYQwLji8uFK zHrMFkJhas6MX7_)fQOUAdK+Yd_7Xqmy&h#yP*-z-O(q02e>iefv9%Isl^mcJBexQ~ zQA`!IN397pf3omDR%HXNfro<;!)`{Cna0QOJ?Zo6bpFvwzGrxNdF8+{w?8WsK-) zhrjrD`!PdXeOXBvmR5-YoFlOMPUH_xOJn;~3^ce@rKV52{OSdNj{|teibHvx)-<^( zi04yTQQ--O&@dvlh-RK;6d1CqAQ#IOOhPwDx(iVs5X1;qcaNO(4-sM4-h#~r*-UXq z%+v3a3&ztXv;;R_3JutjGTkrV^rvh`RFtz26ndSnaFIgU>l&dNZnDuq(6l($eEVjt z4w}655z@{!%X%RqqB8_XS!+8<&VuQ2x7eHyom`+68IGfn!Q~yj@PJv&G{Tj^xVWsd z76=>FdemvEP15upLGbzdA1Z#U!6orgDgp5R&{wzHCjklHc`~TxWfL<=I;7}r?iB13 zMf8cFO8-U-dF_fo--vqSqNkKC#6tsnD*qlO(wKYYG&+YFi=>J>G*_Fvsx_y_vc8BQ zC5)|2I$Htmldff+;Jw;HKABSeYq8o^b9B)+6KtSa>_g37!(u_E(5a%s=1cew{z;R7 z>l-bFf(HpyHuAhtWul3xaP8s{dP-XBFae5W>2p-xAck9M*u>5f5XE%xWUwh!TH!)F zDr?X@Y7x9FnLJ3DZvO(F%}@DuSDdbMj~A{PRi?{VZaW1`9yh%Km~15&2iDD)HTz_alTFA}Itq1M@QxY@; z>QYn(*~P;F3Raby5)fA_xf@wR@KQqGkC~+c3+Dl$xOjaHbe)XA6lTAr* z)O4Asn|<>5m3$(45t@>kwlN|=hfwA*j`TE45_iD@6OxiLDRO>a8*fb}s$SmOnS)Tz zFO-##B%-Pie9Pm(LX)r|hw%UhVv3bu9x?9&YNw zH@9d@-1WWb!@s|E>)Blw{4eX-TTR8%j+K%SK4Zna96^Y5b4*th-*Q{o4)hb#?-=0P ztJce$#^C+4#mbCP!Zg_`f}a3R_y%%`(#ovd2+qcn?w=~~S#JpzO5z?KVKE$U{V6&O zlLag#Wi7IJ>!Qj#tJ%zm*?ey+~?ANe|S{(Up~`X9%7miam*e40XhJv$xgf6uo# zDcleog!NI(wIT^6#NH!`lIQV@U&&jXvhthnV>zm>94)}VO_%xej)u2$ISXBmXJmv(FYFBI810_k`i?c_Ac( zxO0sD_4?IGPB@|0ZO%j18zGLcPXO*2lM6&*y8v%h;rI;f8%T&Wk_HYBq zdQQ4KI5{WESbNzD6Usj64xux-K+W-cq~mTQA1WL93`)R;L(N*M z-w^?AowbJ%XfHsn=VCMd=I9zjaZ|pEahXv@DK^?5@An#)k(4^U+wkY`Mqm5XfXsIn zlbHQ7(%-$m4R2);wl=HhAuY%t{F@dk5JXVWu}GrWx?Z?cMU*#Mkk@MR(8vCkJRi!Q z)BZ`5XMrmSfOO6&nsD~$M4(D+k?(!G%N6p4twb+h@UbHuPbRSp1H}1J4q!|(dEJmH z8c(eUT7QG>(yB7F)1z4(kB^iRZydhc!e1+wMCpiUKZA*=Pu72*<$dC#)d$QFv{hR* zW$u#nQ6D#HWYh1*d+5xmX?!~7$bS@Oz-$z9d~UPtm*t)6X0XY$`e+SWkYYkmu)galX;|5)pS%c{6VnXVyBwu4 zjiG}8n9wwC-9PEHjO+=GOF;9wmm5dwBB-dl0-ha2MlDu_7j`2C`lhFiC7vqN+2~4S zV-E0KJYR<61V2G%*=32eQk1;Genln5gbBkDI+&yZ|A%bgu%bYw80P3F~-}Cpc#uPJCBnZf_5Ihb}xz}E*Brj49qoigx6V&kWZCI#j${U}-#NgK)a0IBC2oYs(5SkeX2;_T{g7Q>_HyS3jYV>AaAyJScb16wpJ0Z z&DEf57Be~}(x;+|Q`NFQgoBE!)wzsdr%#^%VHMc3y?taItdN@Xk~XbOveM2$4nU`K zjd6!{mftw}Z#^>8JqEOgd}3gER65QhK3lO{_a;Dj^br3X0sz0AIK<;yc!~m_rL<{R zb8G#C)G)4?%9kGwZ=B(kMAhYxi`BoHFSYvgZ0mAvolLIWG9c-V%@$Z>M)>bA2ObW% zR`1~t2a}e8r#kOdIToJmQbI`{RR0dPzsEwf;h*oC)csZ&KsRz!_P=3ssu%9|}K!IHp6eL~tQGDkraEVU=6>cJDp25?2{?NB(7xlVm(R*+@t+L3PTO0{7Fr0&XR z-;`|2SPG2#w=-?kHPrdWrkUqL^u}Ajt4ZKfo@YR)%%k@K(D!k8I6jTclM7BNl46^- z(iN}|ZJ2#nckk(K04+lBE5$$4S+5o%fgewc!_p`J0Pp33K*ito&{Ye(JP!Q8Q`slS zEhPTQip^W&{=)X|1d!jQrd1|(Lktzy*e&=Qq=sv&UAPl$xC3J zc@!#gqsnq+VP(q;rmA6G=ex2@CS<*wS;BjQIzzYE3@MDmGuX!wC#e;H{?UTcLqx%2 z9k$kd#>2%ivf3p^>f4{yE?pQEcR3ekIW^*|KGJU;T!^r^u?NZj*d*{s9i7WWL!)~Ep3s~9LGOI_Z>|`kbPCOe zBX|A#jmy%pS0JkXGon)b=?F89riLnZG1Ynyu=y_#+ygKUbe2qsiGPH%&=I%=J)!|dmTbCgsWWN{QV#^;vR8`&iw;xdGaWMa2V)aq_y zpiE%$VG?L8)9XIjvAAUKZ$k~QX_t)${TfpmfOU#}N)y~z!pFBfkO)TG2lFZvjRjWtS0YnVKBlU-GD7wgZ|7fjK$+ zt~gdc=*$}-)=S@#PvIcbcPos5G%l0Y^V>4zV+Cquxy{NRNZ84slXIN8{MB4=yEaMk z8Osc7y%r9EThqJCyQG}A&ScsvN8_O*s0TOycsBsw){=pj;$lXgY%C<<3`N{UxUd`z z*{lQ21wa%bj-U#k>3d7yzFIkwiT3|QFmHQ~ z?)`w?wj)^KO7bRn|9K-BRV$nwfDSTLnqd#(Hc{kuj2<;9lI5`Fq>{ED61XgFDQ16% zAA-t0>e$1JrK9xS_l<}Xg6WOVrcW!7*TkM;&tV=~)(y;jwIm;R5w+I6%MV8^HG5gx zbztZXXFlhikHb9@u zOw{4d1;8VA^X6AmmCGP`bWZ2DZk-y&|3100jG z!}=z%xG%T*4ZXsS*eNb6#kbG!xnKfCM!oAQ5ikw8yl>{@6A=%}K+PMaF<7?}Ie=JJ zKrw9?&M%gQXr_V(TgTAy6w0NaCq*_UIKw zr@#f}XJL4OaJFQf!VQVg`R>a%s3A&XM~{pM_{oF~y@S1ZzwnWY;Jq5^N>M+7_$GwW zzzHh%0iJrds9F`3@|&bH6N-eZ2s}JD&h`l*uOr)-C~uc+DYKhXD!Z19FS=aLf|U7R zcQ|=fAS+5^#J-yuj`Rm-X^M6|c!?jbAaz7y$>kh?Gtar5j^qAV@T63a&JvYGMIA4Q zbe5derS?tYa76$V2B9Cq^HE2Uddrp*|$mr5|!ik+enGn)~Ks z|8D!%kec&4_40x3a{x82+$;2l@~=N7TZC~{%(K(BU%aVg2{v?z@8rpSq|J<58& zl#rszCr&m{yyHG`9BTSo=0*DyBIYlnQ_MM)A#`vz_ytxWKEYWxM?uu`={nTPfECO7 zYJf7d4T_J1V>#sytOy%a1#^%ZGA#`Q#0BeX_l~Z*C-}4-ze24GTmNHtL}_ak7rf$} zwHa3<8Mrq~{XVv81g3U`xI#7nElbWLM{hESYnNrrQ(683Kqw0$!MZq?A@2JV-(xN3 zBK;+DqE95dHA zuKm1PBP3g5uA>Rk2+6%V8Z1j7Dg~oFQ}2Smu`{j=DBi64&9tX^PnUFV{4lw|QK+B7 z(6CUb3e&IN5N8M@XS!uyUNoNa0M!pOmFT}_ox_VI)~L_uyZY)8();252YsSty zsdjHY%SD=jh`8k=sov7R>8P8anySX|DY=vlIt|wn0IQLH(mE{{nauBdG!lwtBz{#L z0^E#AwUf1*8$mC*kjf9%?@sszzF1BCdU5$FN-^%xFfY4IB2L5w6qv%-OAU{5p9-G( zRQ%kxkp!Fr1+gV}wNu58b_igcKOrQvNC23rlVPW70mpn^Ac$4AYX5(zbps1xIYroh zcF0+OPoCilnf(|ER3DwJFPbd$M~rEY#-Ek33x+hg+5@&IAfKv_5Ja%$7igW06j_Fg z!QjsnDiv0_UpDScymtYo{xDVRp^2c5tx!xTyzY^BA?Z|JC}KemllGPMM*4wyRwV;Y zVamzKc&hm-4eYVfkHR{cj)Zl85!l*@kQ#qhc6ijDVj(B28gd~$<@?v@r7&^p z_^n;r19!SGW^W|#?;{+Z;I_KxBbN^foV@aFRs0T>!fD$?g`d*A{y=N3`A1Oi6+&yF z&&`*v?+&M9exGU*ZcEQI5Bpt8XgAC5*`!xqp^q;O4xD5E5s0MQV^%l5PcJlI;F29O z1<9(Tj~tf`bt7!c2vPWyZ7`Q#p$IRjYWU(+*fPhG4kF2MhQ3l<z_Y{~8F(p1@#*(JwITG)3g+?UP`X*=FSa{$69Sj>IC%n>+9 zl~G{{7bHb{YE@O$s~F8c?3B&0*ue8t=DAE9fR^Czx!AokXRv%2-%PWkMv1lXA3-$q z#BJD8p_7;q?eGxjE1!Rq&bk7|LQ7HD>mv8pnq8Zz=!22J)zIt2ojxdW{_KCcfeKBG zcI&NKw!I!l>Pa{>Pb<~riBu7_bIp+q!cuzP+hqSJR^UkAbnvOi36!0a^Ok`g>~5{X)u+{vwnItD@wCq2HjVP#VI~K}=mUp1(qG&80$XC|QigGUMOHyeMBBy^YL9z5(#=z7ZlWfBQBoH3+oU`MDvmDOU0 z3EuEmkOE^gZ?{`H!|gV!MNBauOzU#M|oDuR0!P9?`tUsZ>|95d}qpFeR z`v@r#N4}zA=Xa)&T2P;#ODl~mFy!X}V6QzU*&0AVWqM&eB8~Y}*YL|+$qBKF`1JjzDQMy8{WjnI; z5D?4b+*Jv#JIa81pTl-GM!L>Q%}BlWtcZCm%t4mWCss{Q1?3XcNY3xvfuTUpyn;%t zNwGc9O0`YNRTN9o2OyIX{Dv^tp}pgRaJ)scsN-a<(JBDWt$? zEnJ{fbEc5le{R@_I9?$2Kq~PkPLvMh;*YnYiGLr}ML7NEr8Vn86igS+#u6kp%H_0t zA;U01-l8r+m{h+i~qI)w`)Zaypyx_YvJ%vY~w_f$pe4G(&;eg<-5+?fx?k=OpWAS{-5UZaMH6Q_XyMkR-r&xrzg zV%>wB{a0?Km^NE8kv8;-9UPM#X0_x|LK)v<*VuQ6+B4#|tQuyN5}n5EzLA{GidIqO z&)9@y5Hf_Shnc4w1^_&f2j-$YZIJY9im_M_ytoD*?OzesW57&*T!qto1;-lKt1f*I z=2ZVLdXJ~#Z{g%Bg=4(89!sq0c%`lnPYO9x!pQY{NBXXR9|Q=s;|tJ_MN`9VaJ4a% zktZuUY}|uWaMOHZCb)o+qq5HKRqAX7X3ZyJS#XKU(Kqv&@aNd9PfW$}Cok+M{nzOk_s=e#(+Zh(>APY1`(`qNvx?^OP@vt$;H3L*D| zZKW`M=}#~{UX`rB>*t850XJm{q|r{(-z$a#BE6GMC&jP~(b~Bl zmQTnnt;bqJE`-~;+Tq^;F!TRMb0MU`@1rlu44JNLh6e3dOAOj53>bVw%sybzH%uf) zeARR`K}tBDkEWI%VTLKuvmx#{`o+!frGn`T6k)NnkNb2Es}Rs9lrv0+G$t4|-XY8c zYbUo;W7L)*VRiloww7FFd#)p5P=R|y8GV1K#cBSgYfj~^Tb-z-p17w za6Pvh~s z9BemDSRuW!-RI{ppM(}9T@^rHl*Z+?GU`o7BwpN_7g};)SZif#&BGVqvXnxhj+2L- zvogau<+(So=>sWv)TC92I}~<2((qBV+QLK0*dPaEiY{8HitQ|NoZRk*_BMrnWr!Rw>qRuc!;>#u>{*n|0*hZx65gQ7 zRMgw;tNQrm`s2n9y?hR(&G+re3t;?Ddl=eApo)BnOB9hpd5M=yKJ=>1*U28N8cT-d zSc&yHawIEU?wsAl8^PW=xQQuvo?teR$=O>m(efH`s^toz-ivoBVe{=pgtnKm+eW}Y zx_bzRsi*{aR5fviO>`00zGXyYeo-+5ghFtjpaDYE|6IeEY{IG8~654kR z(Oxb0M9=tEl<)?8yks~9#_Hd|&nvUJ6nF4Xv;`Id{5gA&LPX0R77Kin>(_f!IyxEk zJrZ|F>}B#r1ZyBtt3i2X|3l1$u@jNbOM*f{Yo8l=rc+PPtu!QJnPuSl59utyl?yV1 z3WPf@cD8p*P}?9>IEVA$Hk7oQs}P*qc^I^GZyc?1KE`|$uIS(2Ir+$S~Aeu z5H=mcvSQq=>aWiF9G3y*ppbNQs1 zg}KLR%CY63Mu1o$0Q^9y=e*WMpa%H|uoWevH@QL|NF#r@X7O0zF6gcA4*wwVVYPDZ z$YqU#H5JFx6;H4g=}2DDNyfuY1YOQjmg~yW&0=Honj4G9?5CqkJdJ4EUpjGbQ=D;d zse{yE4-wrc=wY)&5I3H+(W1h58!KRhjoVx5dh_M7VnJN-7vR8qFZsiaIM=k0lsvIV z%o$wcKIskwRLG3*F%gfKhjL{9J=zntYpW~^wB8#E_MmX=eMad;yo6?HCUW&xzJlYL zPK7`VBP+w>bb39sJ9HG4eV!Ei)L)yE(3(f3k?ewPY4+%OtgumI0O5<2rlFkbFOFD3 zHeG@(jfL-oU)4IhkG?oZ?)QOdvM0A}*WrXn7 z@f|-s9FuEmdrvJhaTsL@@iVq*JT@Mbo_B8POC8duah4}CZsj+&y$q(NHUhP|nJ`aB zN?x9^6@A$(%_S*X38m>jH391CTN2p#R_liWSR*yT8UZ&H$m`HLj$ig9ONl~Ipd2v8 zj~$rUrFwrYRlHcpwW;m92L;2r^g9~&5r@3g29d0QC9InBMFSNACTk-gh*ykxuere4 z77(#N+ykFP`kT(5CkKti!uw)|6ehv%oHESK@dHbEtmx6P-uc0?5u`O#@AieED9k=56fqF zE@Yyb*8!LyKqkTOoZ(ov?5r9Xj>oCAk1DZ!PEBYX%U`03gv>VE`})LuKlO-*@aZ~I zq(b$VO^zs;nKm#=Af5sK3Q!y}_Nb-Qm)OQ;xmFo2tY|-n=Y@!d@5zrI6br*_0dx^YV2YgwT`8U7c&F=#$d|emq zl6#6!aJA7VyBdx4-~l3(0tjPko4(jOJdD@v;u5I^A{1kBm<{CQ7)tKc`WrJa@Yy}D zJsy}#i}w%gC7bFxb%m#oi$H?v`Xs#2$h?k{RTS%!G;XxgV;Z)m!1V}wJVNxm=qSH| z5Nfk7+G&qyX%qsTdcNlP13tVyu{pTfB2H%=19v4pK;DH5)*p||$1Dh@ZT&J3B6YVb zHIlx&n78q|{JN9G0L_Vx+pm`Ey|*ODjV+w+Z0T17SUYWxXwi9D2t}bc`q!BjgRV0B zNn|`d3z70+d$=DUKCJppJ7fQR)`^5x@TXjT{g$LoJxFz}?o@Mt^`$itx(1jt)2zkU zq@Z#|1U(!`weKtO7@PqsS)dJz0_3ZE2aOzK~pV0f$RiOk%>3DjWiQO9wRi1Sek0wK-U?1pXlqHN6paQ2Nm*a#k@4)|O{5B6Q9j&K#95UtOmw?NS z4Cb#iU+fPIhf4Q?W-yWZcN!ll0?9ts<7!4um4h3MA1wFeuYVc0INXt~Kj! zaW{vwi-fwVz#J{Q?d(G7_LHx9Y5<#rpW-vGNV{&PW)(7*+Hn-jcv&dL6=tnX^M)6B1Qg?-*#zi7ngXZkz_!U`pJQ~( zl?a({x3!c@=_{1BsLhuWf+p=YoE3@|P@eIunw^+oJbVx2)e^7_zST#Nkz3c{tV*Wt*ND~ix!c{Wb3AO45Pb7+%}uWOQK+sX$d45PIn{&yO1pX%!| zzEtGYwKom$EIKfB?I|c7@S$m4(gv+PT2iRINH6NP{3VR?=gyfrmA*Y;sW(E8FD>*L zR-7#P@z=Uto0=xv&|}$MOjTFio?r1W&dXc~n}|`}h5CpuX6A#{z$5^yf|&_PegQ{6 zRZZq4!B!#W6BY6CNvJcvv@peBdJ3trLtS#bf>!7WT?tZBKFD24lTe9}WXk!4WXp8u zp+X^Uz@b3<=KX>xFaFdAT?>3J#3dBnlHI{C4VG)D^3tnxo=D7p=fD$gMRr08$?r$UgZ zF&f%<%H41#s611?TOk_kzoMlP^)A`y`M^qqCZ8mo{c=H+c!R=(z?odBR$g9WG2}DC zs5z$)o>z+DKCk~(*>-^ZjS(&cqb8Euq4EVlg22Cq*6tS7GOO@8saBETva7Vu*ITOpme7@@4?Gk8mM z7fszinf&?&H&?n>X=e>go-M5*a1H^zc>y{gu__daB` zBFrAYgT;fyn(|q&#)Y(akkk-uE?G53h5QWbjmrkprkPJLQ~ z&Uw$Vtzmqt95l&jp|^VFqxnsY^cFfmH3vo>ohTp$f1U$(y`BC-_ALSm&OC!L`_@uB zUVZqK76$7S8*ehldwdw?YGBW0Z7m1jugfc2+K9NPPgq|W)6UgP`QEj0 zU~+_EzXf4a{2Rjg=?Im}b+Q_4N>xBjUx_M5?G@(CrCERBungs?8N1S)RRNr6wZpX{MEpJC31k$3~ zG^|tc5$C8oy^pLVh%h7TG7y9IB(@^PU>_;QW5F&_4vV#3gZJNZV824}t%aetpI_}eNE{+Iff_ALJkJZo+ObNo$vdru@N`UVDKAEL4%yELY*WzfETm%>OQS?l94(!hjm{DN-pg^ z2VmLq9J725OjSwF(M9utkv3$WC4<2kNs<;JT1y}1)=>1yj1EP}#C}AM{JWyQf$DH- zu-m3RBzErclgc@&5r5lqWdC>C_l-~92d2bgAzZn=H4Eib+!nyxO0_wn{%Gmklw_^D z#o4O7nL29ICR^~-kt}yeD2;h9E36_>6jpPZ)s{WxsI}Ztir)eRnuFNXU`m=P!;qLr zRTgkadk*(Z>k1I-kRL$_g3EHKgf zL(}#Y;t?_9(# z;J#$%tR)i{B{Igi9(;<8UEv!$Jh1;zZ`ky#T3YVzmfM0pEElG1@n?6#ek{3(Rhhi< zI&eZ)IeF_5tPF-+Y2@EoF^Mg$zM40UIK(gmN=aN-`H(uNrWf-kL+0baq(l(uk=aeb zdCkkZiTU}{zvwudv{CZO!n1yIt!3cKsC|mUaf4p(TY3PJDAtgMP3|2g5IaqajJED^ zp`pKa`1i^@d(@@pRa^YOLtgq;?j19p->i51@A23(Z6YGa_H!0ETswZ7(HDap_+_ht z0`=AJjwW*O{mg^!*FFBkV(k8@+`E3+U2q?gx%kn!Zxv&Bf|JSJJN#-LH-~11l}d=9 zuy}QR@q69q`bmpQi5dYRki~}NV>6KlwjIBRJFUGQ`MFbrXbB`;p9H;RwysOE z&brC^Zb|zfM8~Kr$!y7&-M2v>puYs>2XWf+@N&Z6QwCo?EbBSz=;yx)#9iU*My5%2VBQhF!%G-)fv zgeiMBXw)OMqe*M-Eoy-N0Yhtb3-Fs=?)wJL*R1UK-)8$JQ9pAB&OBIIHG;R*-IJhk z(cG47Q2J+%qbMh8QAck`0mVCHs9&1U{2R}XZEB?$h1lxAPzK>06xbLi{sPc}kr&;O ze!e#{RsP%~=q>AA;-OpCJnjm5SYc*SrP>xk&pN|;L9kPU@DS)F2{f~;9@mvNTdZK@ zG-tC0!^ghR>u1P;g086O4k*kk* z&Pm7_AM?s3Sq)HUruuRb<0Zy}ZtUY|87gaz1%Z6TX^T9PX;*Z#g!ikHv*SoqAgzO# zir4XWawo-t=N>>1(|6b+KP$u3w7^c++9xDY2*L?XsV$q*bTC!&&Ck=0@FNcu6s9j( zYhZV0ATK1dNdR|&YjxdFc^q^Q!tAt09x-RSj`ZQKmWV)kL$s2#FQD3L-f+-Bns}$% z4aWg`Qv=LYenyYGF1SQ|1gdC6kbxP~66`8vdJ!Vpb@uWSv8l#_Tw}jZ-&_!CeAISG zF6AEk8C<}W+`KOSK#<$8Y0e#xW|6K4+S)PJ+^tcr$?yKxhx>GFwR&G!B zz_1(oYkpquFa6p{+EU*+lGb-VqoF)(6S;WU^cL*KS}UIg2Y9 zVx$HL*)7L9#7>C>6%yqRHI6bdtIYdqwYPb7?a)6;W!~o-{|9^JOd0L)g{C2^pcNoT0Htr*DW=5RJ%P)ySrOzx!jO2siER?LKq=WkXdqV8iwI#;Ofq1U zoXQ|Z0Yqo?a{joUbC>e{r7Qdv$M7DP_zqvRto{jnziHp?2j8?G_M(Up$^Ho+z#sep z|3MFf`iU3y76hMgmNkR}MclF3!3EOO2hnmbHu;g0ks zd%DF^nM&PVU=9!q^HLJFGj$jMYQiRQzz7%TvaBBus2J;G&(bUgi0<>K1h^#9M~TmP zQ<j%NM4(;Od!mXbiw&u$sbhpk5eKiA}? zyubhe00D%AgJuR25;I!5^vDbkDr8QrM*%6ZSr4}^5~ z=n$lcQcl^$yP?A8I%(*h0f!elgFy5;PhL%o?lU?Szo}QAG4$n?=?bk!0Y7^*IW0D7 z2Xxi=LwWe#%*ixQ_N0iYDh=y<8JX?Ye&uZdRaR7FuBr;WE*%FvsggP>5=!DNSGJ6) zMxnVvjBE`_38c2Lp$pY$H6+XiMfBx|mKEnTh{_zz)!53}&CtWRvo4XJA=C-8q zhIn`NjfXc&w#~aG13q?6E6uAp#iVy&13v`^mxsdeRs0>DKT#vJfLS`(FqK*>Q6wdqI>KlZ0E)E>ZNe>+UPuH@O6O9BII*oWF zD)twR)oP9Os&;jY*AlV6X__iO)$U3|nZd~DWWOuLWhZp0av5h&%WN>r;X1iQy>=80HmBg9AktV-Z7L zaap+hIh^CIE4I44>EAnVq4-S-|2h0uRaFZP|6x%L$EYbj;n+GvwlRqq9PBQOd9_P~ Qd4@VZ?u2=%at0dz*~2rT?f?J) literal 36754 zcmeHQcX$-nwI69!4cLyIx_Lcvc9OUS!eV&Ic$~j*xy+R6?4v-4SCnu2~y^NS&3|l z-IQzevsp56@-A@aJM)cxW@oul_E$m8V~qtyKa=a|Xz53+1Wz-Yij02t_vfJWpMiIc ztHkJMwd-l(L*OO%*f$HjyN05FWF=(MRr403pYy$RDf4^Q7n|oS11aVeGU|7bD|7Nj zKZ|pVLiPbGp`*@N^8}$TyE$8^;cyE2ThQ$7M$jzKdbMEv_8SfpP#jlgp!98_Nv>RD zu=(2Cp;8%Vur&h7YEx50D`>$Sw&faq9aT~_>yOK3oN<}-P_?Tz7HeT8#ONDlpgNbM z8rGjdhitalpscfDtdu#&YM3&pdbu;#C^4BhLdW`(*whAZd7E(wM(tpI^_SlH*jV z2@&*W=!c;fErKdruv`#?PCDr_>x8x+7>?EeGaH-Ar6fel8Jfvv0~jVUakPrlq)Jqy zhssL;z!~;DD4c=jvwm1)o>dU)xHJ`IYS^FB5yR6|-00+?k>OC9W$5sjPnB?K zLzrS{W3kXi^Ys*>fc2-)@yETQ8yi<+Q2Zr^i5;T?J-JcCQ`Y}x07)}cXxWZIlRRRqiD4TR_8X?nz%IjUwUi(a} z6hua7&32)fbpp1N^`jLdR9tDQFBc6e2BI5V?K{U|xCVv-Rc8l9EmsoBErPVMhh1h3 zC|<9mp%}x)rE(>J$(RTz_X4rYZgN=oktoTsWb*qkN+k9=3PyyVEPRvIqA~iqR-wD0 z^~w>dVi1-LgY0z>|Ds)k!Ne$!TL<9q+7&e|Of<_Ic z)G)5cH<~msd|j8aq6Tw&9WVqXCfh_=1@K9Wolwfu__pjF)|Vcx0wlPUC^Z1E!KF6_ zTU@7?5Fs;;x~w{A*o9cC62>%Ws|L9nP$akE#G*>Wi}dJYf)gvN(6;$2N*_B zC{6|JTofZr&3xk^lfzm$@|CzEqtk2|hXXfQkM2g(??7YZqqzcLA1!CmELV|nfXQhr zjC*C2!FeH)7OE~4n60NG>Ag^Oq6&Cb!$I#I_7Y=|*>!oN{5O-csA`yE)eeF2q!Ji? z7-fEH5T{CurKut3ETzT(i|f5*^4VOeyYtK1mS=sGc%#+Y)U!%td)vk^G=vA*G> zpi&!>vP+Z_8R;xZoQGiW35o$&I}@hUxZ-KcQrZz|@j)nN3u+iKDo zuRwm57H0ZoyX_x`UC30TFl8mONjC4$JSJxj zfGv~9B#nmYngTP1jy`MM1u(fzE?_XQS-#jD2h5m8;5-C(DMlWhG$s+mOYk?Xraeag zM(3fage)J_S?Uz{j)pTw09!^b*TA)Pt~zM7edkz=$Q81WSQ=PAoNuw4_6kk)PPuF# z>%HV7;Y}Y$kxkX5W)O;j9%bkL?i4TxEkP6i;5YUr=-hSZ=$;BFswLA%?lm z29YSuZ8`=D?lAh8;1(pY9b}lxtPeqH1=XbCZxx&d)%F4b=GJA_Pc;O?yfhgaIgP*M z)yYe{2!dkHpD&&MkU`LC;m+%z(+()SpJpzy17#C!R;T?OKRZr_l3D>CB4y1Xi_2Q` zh{YGpajC(8I2;$N<|p7@E<(zT&26wdE!DsU#_obJFOD?ojDZ%1^YZpZ!x)_xM&*<; z0i#MV8nwhl7?!CfbB@v9;<&X>xH}0b#btO=;=#6;U>Bh~SHUvE*Od?VCxD3UDj+&1oqC!)JK|2Q8?C%V3QpmdgoLiC2S&Nu}o<4s#*s z2_yUh42Ic`e6Y~(kZ=ozZp4Pn-Tpox0{4iUnSuapi&y?8u*E_*4PUuW=qBg}`>99@ zB+$wRSaN`&9WSdARG_*?lhE_#x1j+NS$ZSXCb66w0v2eHFqXy_pLIB$H!n`bE!BKl4CCR1*nBagCV!RpG+?dV6K>GQ}=)(6MC zSCxCqvhO?xM`UVnAR zgWIU0JDG4TK)U$1RVc%3V-Z4+B7~MjNImLQBLWn>dBw0bi)YojSV^<;}TbL(Id zNhTg>hRl!dw4CI^QkyQ(g@Oo%%CTv02i&=BS~+;uqgzo0bkxk7=F%+nhUc<2o15l_ zyl!zAyt%xqt?NS*FE#Ck9KBw5wrvZhIDYF;*1D{$bsJ8!?xCpNt@WGMZ`iPY!@*ni z;Ug`lyX9cZZe1^gG6S>tM#p$8tEDDBIVrpn7QD5s8wX3(=yTG+S*^PU=iTN}sRj*x zZH}uRU)HuO>=n(gga2!c>1x!3rjt>jKnY2@Xd5}wb~!mjgT53Rd7^1T(nBE(eW-cq zU=2Dz8k*Nu_UeM$6=5U^B4B}iGaUmPBOB{Hf>*XJkb*%Y6R%&2P&dC@v{kny;Hr7p z+_nl-uyaIR)0^qdbp)eje}wXF8Ho=orI zx(KQWB9pFNQm7q`t=g8L))uEdd2VYZ@B}l|KB&5>juxuM_}dGFs*7%~M!%^Vn|^Cg z$l|sN%m4$M+J9@tU`kB}Q-h~A?+>kLTM(jwOxQ^4c_yoM@7wyR0n=u(3m(_~#@MF4 zIH4h5CZs!BXG7&w?j8MWWJJAlTqx8tfO>6VYwh6qt-Dczs)DJS-F74`UY!^muX?v> zi=yUMX0#@8Ktjs)*4ohVuFF#*qqQ*sQL?Z_UI{^h_A_SOJeZ(Od^usI#hjdMInB&y zzBDrmD{I?3IzgQ{F#gR`t?NQYnXIc5;-PE(sMzCecI~x5xTRdbcEfZ-cP-f3dLFTGKwcM)3=!g2EU!T%mwz zi!l+fCYQ;T3WZY1Vz7jUf|NqB9X7@}v>#U0x-d*jBa9yM*)&w<-7^I;G&-rNj-&*V zU~mMh!@wEBbTj+HUb+sJBDH^53JZIG+0+jX(@Z1lN3N!E`Cuo#mwov<8SjNO9`$&_14q8*GZb_F@fpv;$W|G{ctdvBYsU_OU|9X{ov zxcUEA-u&+rhDJI3A=FgwPJmi4Cee`uK{1=b4TFcP)~-yzsb2j6HDIlxXD&;RV{n2l zUvXy;o1bK$@AjwPMp84sJjstj7Wwf*QWC*ifl1^XCo4(<6lq zeQ(|Xd`M=^w#wpl(?==^oMLEP{>D1qP_8eNl-HyaeR%_3rl|3o4dqpaiu{!mhlLNB zmQz*5=afnKtqCv>`*aA@urDxp+*(6<84q=o>5HMBGD)SD6}CJ5@d=RBq|z!)nJ-^a zURdU9$iVyK6xab%4v){OE-x+ftx5w!(|@l3Nl)2YRRY+Q#K1nMe_nxIg1DrO2EGWy zWdSVx_6zut%uJpa8a6cy0O_A&U=J)Zu~mk`vY>L!7+44O(=$M%Ru+{7RvP9}{qPJ3 zyLVO#1p=z)3 z@FE@g`qF|*g8}9(+>d*95*!4RNDxZZ;>`;{gI>G@@3Q_hfkz1*yPo|7$GUIYqO(AB z7KqLQ(ODom3q)su=qwPO1){S+j1>3>M+#gN+yU@Rua|HE@EFjv@Ss;p;Ih751_?u@ zVT9l^AVb3!U1@kdl<31{@Eo1UA6q+;3YC&f9&9kN(4_oZYLDL+yN89qLyR+A6|0D2$Z>_juad{^ohmp68Zy-R!s9K!#_3=Fzx)J05fvx_v#nL;LAAphHyGJ)N7~ zlJ>6`LjXzt{RS9W_=Tqg(D`^6Z2kJ}H=sktSv?&^?w@{rO?bf3-*^H)l;%4+gq9Wk z@`v~hsNcNjDRc*QI_C&m*?vV7NTl<-+6&!*U7lK5e;o(ST}AEy&(5&^ISxYeK&Qa= z2eZ(Ac@D^=yPXB@fct-nrTX?9gzobIujf6qFV6us;a*3sI|znbc4%*&gT1iH$FF;G z+`$j5Iqz~r@2&$$*lJIEwmZm^`|~g=yqCxV@EuT5zkdMJtD|GQtS{d|XoW`)3Vfgh z?@#Z(1ANT?-P6G^IR=BdFW-Umv`1jw0G_Bmdi{y8eiZ?#4b7V zC$%T2sc+u_B@G+0@X+0N1YcOs5eDEp0LGz0973`OwlpV9LEFp9(`pK{r)Yj7%$4N(po0RilC2tQY;hA;$#cww`hCZin! z9^o{qpwa2#FpAcKEQVFrRG6Jf{x8H)8(?WP>V2nyNf>NAn)C**5 z#V8?G)1TVg1VN`jW@1OBCCF4}h`@Zo?7WemAf+JUCH%-u5Dw9lOn8(6U4GjJQG|ma zhI&I3N;Ap^7X+UQk(3ObwEl<{A|Z2xkk~Uz!^5I4IDuBm28UB9JI)&oDnyODj!vFy zwI84%06v&OUu7q4Iq!79%Nc>TMw3YhIxT}ZhEc1BhrJppL|)oWI#AYR?54bcX5G2| z&gu~;K5XTFA?_1G7VZ0lVEUIJ_S|f50U*2~mnUpaD}dzdtO6HG5IO992wrp*VQL7t zB)S7G9Trnl1_ned13KU2n1$)s=NJgMoLzm@xh)*343bqqZ(FV=kvVJtjmd_m%OQj# zh>pGp1K7Twf(|2baOMOt?5txht4oL0L4V7apKF;c+Xs&!(b%kb8m0%t8#M@SpF=Dn z&xTmUeD)_eipp3LMKPMePx%ZTYSV3Ya`$*kbL^e=%?K=GR^sYN*++&n?PZ{F`5|D9!uT zuTl*KTW4gf|M@SL>nd3)o0U?-c9s?%IaFU#ymR549fez`Em?t~%T66HD&9S>aMreQ zwVO+JkK9xp3oogJkuhni5t9yZX(<$$tV&Caj$s((+;>K$4JQ-mq4Jotv^atprG$nJ zqDc~uoJEi@#3+(f(?5nltk~%?$Wt(Vfl5P93Ncl54q%7F;HU9YA)X!#jvpCwJWhz2 zr=t%&LsR5K(K?vc1WrEP91W5u$C40Q1F<}BEKZ@dPqjz6Y$%hoV#Bm#dGr*0RdwZC zWG@DZVrN!W=M)(#%lN7^tS5s6Z~ZWM;->0yb=eCQ1q!rBi$v0yRbHN?h#o8wyeCk} ztIGy$n=$ffCaC~sjHU`6^;ab>?7=4C6ROL~OF8_hHVJGN9a&f$lk5?oXw0b-bvd~`4l8og&p5Ok}^L0nNXK_f+X6a{i$XF}5_c}Tr zd>9qhlUe#HMqKcCdD7V)%#v@|j4pM@^X;Chq^FsseBqTyCunoeGjU!Ib}3ZrY47|r z1LvQ%Rsy?34*l5Uv4qNdvP+oy1JCwXd$dcad=?kdlU<@QQnX8=U3vy~Y5qcC1Lw2i z0|efMEkm@N8jcbq2U0zkixfbb%W04zPK#7=I;4`zMtHbh#^oVfxdLP}SA>*ug^&tI z5mNH-D26(UyvJrFkJ}1I8PwB#`U5FL|!8{Lwc@WHlU`X{m2!=G52f;iD z=0PwIg5i1@4}y6R%!6PagnADU40+)whB}J82MFdtFw~v<@W|moFb{(Hhl1U15bOrQ zZV(Kq-VK5w&2@udHwbovU^fVc>t${b>;}PZ5bOrQ-UEa}UO0-Ojw0^?g54k(>dt+5 zz(^f;vJAiWFe zu51KZspWiT-++^&8qR0j{Tu}ONW&qk^AKdYnnSkbA%0gUa@?hS#J}TW=AU6K{N+nf z>#M8#{)%**Ja+RdQ0tz>!1Lve$b(CK`SIp2n`*T@ast${_GYyX%2CWXL zdE_c+b$dI{w}MukE$@B;T0Q6jt-9{DKR~)VIy$>RYFDSm9o&g@-E+I)LZ{A+bf^)Z z&aZOa$UO~$+=ukO7C|25xREYU=|MK6paDE2gTL^28R>wu3(|X_M!VMS(|#XL?rDJy z)OnzBBkiD0yBZiEy$|VqP^arYsDP}DT(kf|;)4+6Cx!n5PxAixzpg)TdksGGfH(c~ zML&}GVG{C_wnv#~k$xIh^en_ambv%C$LG)D?BlLyA@#A$uOFX^XCeY30wMw;0wMw; z0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw; z0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0wMw;0{;pK zJnI)g;p4#1^7mQIvy|@foczsSpQQqwN+jujpPd5ksqg|ky8ELC&q9T-KRzCXAoIN6 z0SFG_{`f<5_$d9OAHweOJVTIwn4%)Lh=7QIh=7QIh=7Q|zYYTM>AD~C`!xM8KZO16 zl!e}PkRN;x=^y)hMe_9e|4aA#f*%3t$J>rBlzxvT{;=?grcYJ|0_E+$d;Yw8$}b-C z44nVXCzSr6g3CXv7ng;}_q${LN|oBQk>g`tmndAD=9KOhP=j`0!iBh0~YY zpJe!a$v66SbMAPO?(sA}S%dt$^b=3g5#x6l;G0=b{3d;eKKKbLf&|`ug5iVjkP#&N zTlBv?sQ4cJmyh=bT`va=`W_uQ@=XQS?-Sul;y3iXr_zyIj~J4kPG9hl-rmF97}V0u zaQ5lN;VPkN2A0)5(t&_(IM4P*|EJMbc}7M16snsUj|+E=yO&Z1lF{#9zp9FA>@&WN4uu3m%Mo-VqM0QkOJ_wTxw;m(*x`DH@>i^oRhS3-fSkEoEEAYc5g{F~r` Qc Date: Wed, 29 Aug 2012 04:28:26 -0500 Subject: [PATCH 114/116] OP-669: Gyros were not being sent at a rapid rate during calibration making the results quite noisy. Now both accels and gyros require a minimum number of updates before calibration completes. Thanks to ti.dyer for the report and fix. --- .../plugins/config/configccattitudewidget.cpp | 61 ++++++++++++------- .../plugins/config/configccattitudewidget.h | 10 +-- 2 files changed, 44 insertions(+), 27 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 10064b835..f0fb825fd 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -63,29 +63,29 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() delete ui; } -void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) { +void ConfigCCAttitudeWidget::sensorsUpdated(UAVObject * obj) { QMutexLocker locker(&startStop); - ui->zeroBiasProgress->setValue((float) updates / NUM_ACCEL_UPDATES * 100); + ui->zeroBiasProgress->setValue((float) qMin(accelUpdates,gyroUpdates) / NUM_SENSOR_UPDATES * 100); - if(updates < NUM_ACCEL_UPDATES) { - updates++; - Accels * accels = Accels::GetInstance(getObjectManager()); + Accels * accels = Accels::GetInstance(getObjectManager()); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + + if(obj->getObjID() == Accels::OBJID && accelUpdates < NUM_SENSOR_UPDATES) { + accelUpdates++; Accels::DataFields accelsData = accels->getData(); x_accum.append(accelsData.x); y_accum.append(accelsData.y); z_accum.append(accelsData.z); - - Gyros * gyros = Gyros::GetInstance(getObjectManager()); + } else if (obj->getObjID() == Gyros::OBJID && gyroUpdates < NUM_SENSOR_UPDATES) { + gyroUpdates++; Gyros::DataFields gyrosData = gyros->getData(); - x_gyro_accum.append(gyrosData.x); y_gyro_accum.append(gyrosData.y); z_gyro_accum.append(gyrosData.z); - } else if ( updates == NUM_ACCEL_UPDATES ) { - updates++; + } else if ( accelUpdates >= NUM_SENSOR_UPDATES && gyroUpdates >= NUM_SENSOR_UPDATES) { timer.stop(); - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); + disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); disconnect(&timer,SIGNAL(timeout()),this,SLOT(timeout())); float x_bias = listMean(x_accum) / ACCEL_SCALE; @@ -95,7 +95,8 @@ void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) { float x_gyro_bias = listMean(x_gyro_accum) * 100.0f; float y_gyro_bias = listMean(y_gyro_accum) * 100.0f; float z_gyro_bias = listMean(z_gyro_accum) * 100.0f; - obj->setMetadata(initialMdata); + accels->setMetadata(initialAccelsMdata); + gyros->setMetadata(initialGyrosMdata); AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); // We offset the gyro bias by current bias to help precision @@ -108,17 +109,22 @@ void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) { attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); } else { - // Possible to get here if weird threading stuff happens. Just ignore updates. - qDebug("Unexpected accel update received."); + // Possible to get here if weird threading stuff happens. Just ignore updates. + qDebug("Unexpected accel update received."); } } void ConfigCCAttitudeWidget::timeout() { QMutexLocker locker(&startStop); UAVDataObject * obj = Accels::GetInstance(getObjectManager()); - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); + disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); disconnect(&timer,SIGNAL(timeout()),this,SLOT(timeout())); + Accels * accels = Accels::GetInstance(getObjectManager()); + Gyros * gyros = Gyros::GetInstance(getObjectManager()); + accels->setMetadata(initialAccelsMdata); + gyros->setMetadata(initialGyrosMdata); + QMessageBox msgBox; msgBox.setText(tr("Calibration timed out before receiving required updates.")); msgBox.setStandardButtons(QMessageBox::Ok); @@ -130,7 +136,8 @@ void ConfigCCAttitudeWidget::timeout() { void ConfigCCAttitudeWidget::startAccelCalibration() { QMutexLocker locker(&startStop); - updates = 0; + accelUpdates = 0; + gyroUpdates = 0; x_accum.clear(); y_accum.clear(); z_accum.clear(); @@ -144,19 +151,27 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); // Set up to receive updates - UAVDataObject * obj = Accels::GetInstance(getObjectManager()); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(accelsUpdated(UAVObject*))); + UAVDataObject * accels = Accels::GetInstance(getObjectManager()); + UAVDataObject * gyros = Gyros::GetInstance(getObjectManager()); + connect(accels,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); + connect(gyros,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(sensorsUpdated(UAVObject*))); // Set up timeout timer timer.start(10000); connect(&timer,SIGNAL(timeout()),this,SLOT(timeout())); // Speed up updates - initialMdata = obj->getMetadata(); - UAVObject::Metadata mdata = initialMdata; - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = 100; - obj->setMetadata(mdata); + initialAccelsMdata = accels->getMetadata(); + UAVObject::Metadata accelsMdata = initialAccelsMdata; + UAVObject::SetFlightTelemetryUpdateMode(accelsMdata, UAVObject::UPDATEMODE_PERIODIC); + accelsMdata.flightTelemetryUpdatePeriod = 100; + accels->setMetadata(accelsMdata); + + initialGyrosMdata = gyros->getMetadata(); + UAVObject::Metadata gyrosMdata = initialGyrosMdata; + UAVObject::SetFlightTelemetryUpdateMode(gyrosMdata, UAVObject::UPDATEMODE_PERIODIC); + gyrosMdata.flightTelemetryUpdatePeriod = 10; + gyros->setMetadata(gyrosMdata); } diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h index 28d389df6..fc1a7f623 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h @@ -49,7 +49,7 @@ public: virtual void updateObjectsFromWidgets(); private slots: - void accelsUpdated(UAVObject * obj); + void sensorsUpdated(UAVObject * obj); void timeout(); void startAccelCalibration(); void openHelp(); @@ -58,14 +58,16 @@ private: QMutex startStop; Ui_ccattitude *ui; QTimer timer; - UAVObject::Metadata initialMdata; + UAVObject::Metadata initialAccelsMdata; + UAVObject::Metadata initialGyrosMdata; - int updates; + int accelUpdates; + int gyroUpdates; QList x_accum, y_accum, z_accum; QList x_gyro_accum, y_gyro_accum, z_gyro_accum; - static const int NUM_ACCEL_UPDATES = 60; + static const int NUM_SENSOR_UPDATES = 60; static const float ACCEL_SCALE = 0.004f * 9.81f; protected: virtual void enableControls(bool enable); From 60051e88cc8676f73d738096edf6e3b30d6fedd1 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 30 Aug 2012 11:38:15 -0500 Subject: [PATCH 115/116] Calibration: Fix both accels and gyros to 30 ms. Should be reasonably sustainable through USB. --- .../src/plugins/config/configccattitudewidget.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index f0fb825fd..fe1f517bf 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -164,13 +164,13 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { initialAccelsMdata = accels->getMetadata(); UAVObject::Metadata accelsMdata = initialAccelsMdata; UAVObject::SetFlightTelemetryUpdateMode(accelsMdata, UAVObject::UPDATEMODE_PERIODIC); - accelsMdata.flightTelemetryUpdatePeriod = 100; + accelsMdata.flightTelemetryUpdatePeriod = 30; accels->setMetadata(accelsMdata); initialGyrosMdata = gyros->getMetadata(); UAVObject::Metadata gyrosMdata = initialGyrosMdata; UAVObject::SetFlightTelemetryUpdateMode(gyrosMdata, UAVObject::UPDATEMODE_PERIODIC); - gyrosMdata.flightTelemetryUpdatePeriod = 10; + gyrosMdata.flightTelemetryUpdatePeriod = 30; gyros->setMetadata(gyrosMdata); } From 2c003d8b0b7e088dfb8c6603284677bc2e8df432 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 1 Sep 2012 16:49:15 -0500 Subject: [PATCH 116/116] PathCompiler: Link up the path compiler to the map again. Got broken in the merge. --- .../src/plugins/opmap/opmapgadgetwidget.cpp | 94 +++++-------------- .../src/plugins/opmap/opmapgadgetwidget.h | 5 +- 2 files changed, 28 insertions(+), 71 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 01d006cf7..4405d2b2e 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -267,6 +267,11 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) m_statusUpdateTimer->start(); m_map->setFocus(); + + // Create the path compiler and connect the signals to it + pathCompiler = new PathCompiler(this); + connect(pathCompiler, SIGNAL(visualizationChanged(QList)), + this, SLOT(doVisualizationChanged(QList))); } // destructor @@ -476,13 +481,10 @@ void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) contextMenu.addSeparator()->setText(tr("Waypoints")); - contextMenu.addAction(wayPointEditorAct); contextMenu.addAction(addWayPointAct); if (m_mouse_waypoint) { // we have a waypoint under the mouse - contextMenu.addAction(editWayPointAct); - lockWayPointAct->setChecked(waypoint_locked); contextMenu.addAction(lockWayPointAct); @@ -1295,11 +1297,6 @@ void OPMapGadgetWidget::createActions() followUAVheadingAct->setChecked(false); connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); - addWayPointAct = new QAction(tr("&Add waypoint"), this); - addWayPointAct->setShortcut(tr("Ctrl+A")); - addWayPointAct->setStatusTip(tr("Add waypoint")); - connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); - overlayOpacityActGroup = new QActionGroup(this); connect(overlayOpacityActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onOverlayOpacityActGroup_triggered(QAction *))); overlayOpacityAct.clear(); @@ -1443,71 +1440,30 @@ void OPMapGadgetWidget::createActions() uavTrailDistanceAct.append(uavTrailDistance_act); } -// // GPS trail -// // TODO: Delete this action ? -// showGPSAct = new QAction(tr("Show GPS"), this); -// showGPSAct->setStatusTip(tr("Show/Hide the GPS")); -// showGPSAct->setCheckable(true); -// showGPSAct->setChecked(false); -// connect(showGPSAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPSAct_toggled(bool))); + //GPS trail + showGPSAct = new QAction(tr("Show GPS"), this); + showGPSAct->setStatusTip(tr("Show/Hide the GPS")); + showGPSAct->setCheckable(true); + showGPSAct->setChecked(false); + connect(showGPSAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPSAct_toggled(bool))); -// gpsTrailTypeActGroup = new QActionGroup(this); -// connect(gpsTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTypeActGroup_triggered(QAction *))); -// gpsTrailTypeAct.clear(); -// QStringList gps_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); -// for (int i = 0; i < gps_trail_type_list.count(); i++) -// { -// mapcontrol::UAVTrailType::Types gps_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(gps_trail_type_list[i]); -// QAction *gpsTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(gps_trail_type), gpsTrailTypeActGroup); -// gpsTrailType_act->setCheckable(true); -// gpsTrailType_act->setChecked(gps_trail_type == m_map->GPS->GetTrailType()); -// gpsTrailType_act->setData(i); -// gpsTrailTypeAct.append(gpsTrailType_act); -// } + /** Actions for way points **/ + addWayPointAct = new QAction(tr("&Add waypoint"), this); + addWayPointAct->setShortcut(tr("Ctrl+A")); + addWayPointAct->setStatusTip(tr("Add waypoint")); + connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); -// showGPStrailAct = new QAction(tr("Show Trail dots"), this); -// showGPStrailAct->setStatusTip(tr("Show/Hide the Trail dots")); -// showGPStrailAct->setCheckable(true); -// showGPStrailAct->setChecked(false); -// connect(showGPStrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailAct_toggled(bool))); + clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); + clearWayPointsAct->setStatusTip(tr("Clear all the waypoints")); + connect(clearWayPointsAct, SIGNAL(triggered()),this, SLOT(onClearWayPointsAct_triggered())); -// showGPStrailLineAct = new QAction(tr("Show Trail lines"), this); -// showGPStrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); -// showGPStrailLineAct->setCheckable(true); -// showGPStrailLineAct->setChecked(true); -// connect(showGPStrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowGPStrailLineAct_toggled(bool))); + deleteWayPointAct = new QAction(tr("&Del waypoint"), this); + deleteWayPointAct->setStatusTip(tr("Delete this waypoint")); + connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered())); -// clearGPStrailAct = new QAction(tr("Clear GPS trail"), this); -// clearGPStrailAct->setStatusTip(tr("Clear the GPS trail")); -// connect(clearGPStrailAct, SIGNAL(triggered()), this, SLOT(onClearGPStrailAct_triggered())); - -// gpsTrailTimeActGroup = new QActionGroup(this); -// connect(gpsTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailTimeActGroup_triggered(QAction *))); -// gpsTrailTimeAct.clear(); -// list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); -// for (int i = 0; i < list_size; i++) -// { -// int gps_trail_time = uav_trail_time_list[i]; -// QAction *gpsTrailTime_act = new QAction(QString::number(gps_trail_time) + " sec", gpsTrailTimeActGroup); -// gpsTrailTime_act->setCheckable(true); -// gpsTrailTime_act->setChecked(gps_trail_time == m_map->GPS->TrailTime()); -// gpsTrailTime_act->setData(gps_trail_time); -// gpsTrailTimeAct.append(gpsTrailTime_act); -// } - -// gpsTrailDistanceActGroup = new QActionGroup(this); -// connect(gpsTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onGPStrailDistanceActGroup_triggered(QAction *))); -// gpsTrailDistanceAct.clear(); -// list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); -// for (int i = 0; i < list_size; i++) -// { -// int gps_trail_distance = uav_trail_distance_list[i]; -// QAction *gpsTrailDistance_act = new QAction(QString::number(gps_trail_distance) + " meters", gpsTrailDistanceActGroup); -// gpsTrailDistance_act->setCheckable(true); -// gpsTrailDistance_act->setChecked(gps_trail_distance == m_map->GPS->TrailDistance()); -// gpsTrailDistance_act->setData(gps_trail_distance); -// gpsTrailDistanceAct.append(gpsTrailDistance_act); -// } + lockWayPointAct = new QAction(tr("&Lock waypoints"), this); + lockWayPointAct->setStatusTip(tr("Lock a waypoint location")); + connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered())); } void OPMapGadgetWidget::onReloadAct_triggered() diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 8c9870590..f2413a418 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -275,13 +275,14 @@ private: QAction *goUAVAct; QAction *followUAVpositionAct; QAction *followUAVheadingAct; - QAction *wayPointEditorAct; + QAction *homeMagicWaypointAct; + + // Waypoint actions QAction *addWayPointAct; QAction *editWayPointAct; QAction *lockWayPointAct; QAction *deleteWayPointAct; QAction *clearWayPointsAct; - QAction *homeMagicWaypointAct; QAction *showSafeAreaAct; QAction *changeDefaultLocalAndZoom;