Commit b5af9b84 authored by Alejandro's avatar Alejandro

Save configuration layer view in MapWidget

parent ea95dd0b
......@@ -115,6 +115,11 @@ void MapWidget::init()
lastZoom = settings.value("LAST_ZOOM", lastZoom).toInt();
settings.endGroup();
settings.beginGroup("QGC_HOMEPOSITION");
homeCoordinate.setY(settings.value("HOME_LATITUDE", homeCoordinate.y()).toDouble());
homeCoordinate.setX(settings.value("HOME_LONGITUDE", homeCoordinate.x()).toDouble());
settings.endGroup();
// SET INITIAL POSITION AND ZOOM
// Set default zoom level
mc->setZoom(lastZoom);
......@@ -140,6 +145,14 @@ void MapWidget::init()
connect(mapproviderGroup, SIGNAL(triggered(QAction*)),
this, SLOT(mapproviderSelected(QAction*)));
//mapSettings.beginGroup("Map_Widget");
//QAction *act = new QAction(mapSettings.value("QAction").toString(), this);
//mapproviderSelected(act);
//mapSettings.endGroup();
// Overlay seems currently broken
// yahooActionOverlay = new QAction(tr("Yahoo: street overlay"), this);
// yahooActionOverlay->setCheckable(true);
......@@ -277,10 +290,49 @@ void MapWidget::init()
connect(geomLayer, SIGNAL(geometryEndDrag(Geometry*, QPointF)),
this, SLOT(captureGeometryEndDrag(Geometry*, QPointF)));
connect(homePosition, SIGNAL(geometryClicked(Geometry*,QPoint)),
this, SLOT(captureGeometryClick(Geometry*, QPoint)));
connect(homePosition, SIGNAL(geometryDragged(Geometry*, QPointF)),
this, SLOT(captureGeometryDragHome(Geometry*, QPointF)));
connect(homePosition, SIGNAL(geometryEndDrag(Geometry*, QPointF)),
this, SLOT(captureGeometryEndDrag(Geometry*, QPointF)));
this->loadSettingsMap(settings);
this->createHomePosition(homeCoordinate);
qDebug() << "CHECK END";
}
}
void MapWidget::loadSettingsMap(QSettings &settings)
{
index = 0;
settings.beginGroup("QGC_MAPINDEX");
index = settings.value("MAP_INDEX", index).toInt();
settings.endGroup();
switch(index)
{
case 0:
mapproviderSelected(osmAction);
break;
case 1:
mapproviderSelected(yahooActionMap);
break;
case 2:
mapproviderSelected(yahooActionSatellite);
break;
case 3:
mapproviderSelected(googleActionMap);
break;
case 4:
mapproviderSelected(googleSatAction);
break;
}
}
void MapWidget::goTo()
{
bool ok;
......@@ -322,6 +374,7 @@ void MapWidget::mapproviderSelected(QAction* action)
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
homePosition->setMapAdapter(mapadapter);
index = 0;
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
......@@ -339,6 +392,7 @@ void MapWidget::mapproviderSelected(QAction* action)
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
homePosition->setMapAdapter(mapadapter);
index = 1;
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
......@@ -356,6 +410,7 @@ void MapWidget::mapproviderSelected(QAction* action)
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
homePosition->setMapAdapter(mapadapter);
index = 2;
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
......@@ -370,6 +425,7 @@ void MapWidget::mapproviderSelected(QAction* action)
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
homePosition->setMapAdapter(mapadapter);
index = 3;
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
......@@ -385,6 +441,7 @@ void MapWidget::mapproviderSelected(QAction* action)
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
homePosition->setMapAdapter(mapadapter);
index = 4;
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
......@@ -700,6 +757,38 @@ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
if (!setHome->isChecked())
{
mc->setMouseMode(qmapcontrol::MapControl::Panning);
if(mav)
{
// Update homePosition
UASManager::instance()->setHomePosition(
static_cast<double>(homeCoordinate.x()),
static_cast<double>(homeCoordinate.y()), 0);
}
}
}
void MapWidget::captureGeometryDragHome(Geometry *geom, QPointF coordinate)
{
if (isVisible()) mc->updateRequest(geom->boundingBox().toRect());
Waypoint2DIcon* point2Find = dynamic_cast <Waypoint2DIcon*> (geom);
if (point2Find)// && wps.count() > index)
{
// Update visual
point2Find->setCoordinate(coordinate);
homeCoordinate.setX(coordinate.x());
homeCoordinate.setY(coordinate.y());
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(homeCoordinate.x(), homeCoordinate.y(),"g");
if (isVisible()) mc->updateRequest(tempPoint->boundingBox().toRect());
}
}
MapWidget::~MapWidget()
......@@ -1071,7 +1160,19 @@ void MapWidget::hideEvent(QHideEvent* event)
settings.setValue("LAST_LONGITUDE", currentPos.x());
settings.setValue("LAST_ZOOM", mc->currentZoom());
settings.endGroup();
settings.beginGroup("QGC_MAPINDEX");
settings.setValue("MAP_INDEX", index);
settings.endGroup();
settings.beginGroup("QGC_HOMEPOSITION");
settings.setValue("HOME_LATITUDE", homeCoordinate.y());
settings.setValue("HOME_LONGITUDE", homeCoordinate.x());
settings.endGroup();
settings.sync();
}
}
......@@ -1144,29 +1245,34 @@ void MapWidget::createHomePosition(const QMouseEvent *event, const QPointF coord
{
if (QEvent::MouseButtonRelease == event->type() && setHome->isChecked())
{
homeCoordinate= coordinate;
Waypoint2DIcon* tempCirclePoint;
this->createHomePosition(coordinate);
}
}
double latitud = homeCoordinate.x();
double longitud = homeCoordinate.y();
void MapWidget::createHomePosition(const QPointF coordinate)
{
homeCoordinate= coordinate;
Waypoint2DIcon* tempCirclePoint;
tempCirclePoint = new Waypoint2DIcon(
latitud,
longitud,
20, "g", qmapcontrol::Point::Middle);
double latitude = homeCoordinate.y();
double longitude = homeCoordinate.x();
QPen* pencil = new QPen(Qt::blue);
tempCirclePoint->setPen(pencil);
tempCirclePoint = new Waypoint2DIcon(
longitude,
latitude,
20, "g", qmapcontrol::Point::Middle);
mc->layer("Station")->clearGeometries();
mc->layer("Station")->addGeometry(tempCirclePoint);
QPen* pencil = new QPen(Qt::blue);
tempCirclePoint->setPen(pencil);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(latitud, longitud,"g");
mc->layer("Station")->clearGeometries();
mc->layer("Station")->addGeometry(tempCirclePoint);
if (isVisible())
{
mc->updateRequest(tempPoint->boundingBox().toRect());
}
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(latitude, longitude,"g");
if (isVisible())
{
mc->updateRequest(tempPoint->boundingBox().toRect());
}
}
......@@ -1176,10 +1282,14 @@ void MapWidget::createHomePositionClick(bool click)
if (!setHome->isChecked())
{
UASManager::instance()->setHomePosition(
static_cast<double>(homeCoordinate.x()),
static_cast<double>(homeCoordinate.y()), 0);
if(mav)
{
UASManager::instance()->setHomePosition(
static_cast<double>(homeCoordinate.y()),
static_cast<double>(homeCoordinate.x()), 0);
qDebug()<<"Set home position "<<homeCoordinate.x()<<" "<<homeCoordinate.y();
qDebug()<<"Set home position "<<homeCoordinate.y()<<" "<<homeCoordinate.x();
}
}
}
......@@ -40,8 +40,7 @@ This file is part of the QGROUNDCONTROL project
#include "QPointF"
#include <qmath.h>
#include <QSettings>
class QMenu;
class Waypoint;
......@@ -154,6 +153,8 @@ protected:
void captureGeometryDrag(Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(Geometry* geom, QPointF coordinate);
void captureGeometryDragHome(Geometry* geom, QPointF coordinate);
void createPathButtonClicked(bool checked);
/** @brief Create the graphic representation of the waypoint */
......@@ -161,13 +162,14 @@ protected:
void mapproviderSelected(QAction* action);
void createHomePosition(const QMouseEvent* event, const QPointF coordinate);
void createHomePosition(const QPointF coordinate);
void createHomePositionClick(bool click);
void loadSettingsMap(QSettings &);
signals:
void waypointCreated(Waypoint* wp);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
private:
Ui::MapWidget *m_ui;
QList<qmapcontrol::Point*> wps;
......@@ -178,6 +180,7 @@ private:
int wpExists(const QPointF coordinate);
bool waypointIsDrag;
QPointF homeCoordinate;
int8_t index;
};
#endif // MAPWIDGET_H
......@@ -41,7 +41,7 @@
<bool>true</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 0, 0,50%);</string>
<string notr="true">background-color: rgb(135, 206, 235);</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
......@@ -67,6 +67,9 @@
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="lbPixel">
<property name="styleSheet">
<string notr="true">font-color:rgb(0, 0, 0);</string>
</property>
<property name="text">
<string>----</string>
</property>
......
......@@ -80,11 +80,11 @@ void UASControlParameters::changedMode(int mode)
if(modeTemp != this->mode)
{
ui->lbMode->setStyleSheet("background-color: rgb(255, 0, 0)");
ui->lbMode->setStyleSheet("background-color: rgb(165, 42, 42)");
}
else
{
ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)");
ui->lbMode->setStyleSheet("background-color: rgb(85, 107, 47)");
}
}
......@@ -104,12 +104,17 @@ void UASControlParameters::activeUasSet(UASInterface *uas)
void UASControlParameters::updateGlobalPosition(UASInterface * a, double b, double c, double aa, quint64 ab)
{
//ui->sbHeight->setValue(aa);
Q_UNUSED(a);
Q_UNUSED(b);
Q_UNUSED(c);
Q_UNUSED(ab);
this->altitude=aa;
}
void UASControlParameters::speedChanged(UASInterface* uas, double vx, double vy, double vz, quint64 time)
{
Q_UNUSED(time);
Q_UNUSED(uas);
this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
//ui->sbAirSpeed->setValue(speed);
}
......@@ -117,6 +122,8 @@ void UASControlParameters::speedChanged(UASInterface* uas, double vx, double vy,
void UASControlParameters::updateAttitude(UASInterface *uas, double roll, double pitch, double yaw, quint64 time)
{
Q_UNUSED(uas);
Q_UNUSED(pitch);
Q_UNUSED(yaw);
Q_UNUSED(time);
//ui->sbTurnRate->setValue(roll);
this->roll = roll;
......@@ -194,7 +201,7 @@ void UASControlParameters::updateMode(int uas,QString mode,QString description)
this->mode = mode;
ui->lbMode->setText(this->mode);
ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)");
ui->lbMode->setStyleSheet("background-color: rgb(85, 107, 47)");
}
void UASControlParameters::thrustChanged(UASInterface *uas, double throttle)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment