Commit c7bec2b0 authored by lm's avatar lm

Temporary fix to map widget issue

parent 58f497f3
......@@ -58,7 +58,6 @@ UASManager* UASManager::instance()
UASManager::UASManager() :
activeUAS(NULL)
{
systems = QList<UASInterface*>();
start(QThread::LowPriority);
}
......
......@@ -1990,8 +1990,6 @@ void MainWindow::presentView()
// VIDEO 2
showTheWidget(MENU_VIDEO_STREAM_2, currentView);
this->show();
// Restore window state
if (UASManager::instance()->getUASList().count() > 0)
{
......@@ -2007,6 +2005,18 @@ void MainWindow::presentView()
restoreState(settings.value(getWindowStateKey()).toByteArray(), QGC::applicationVersion());
}
}
// ACTIVATE MAP WIDGET
if (headUpDockWidget)
{
HUD* tmpHud = dynamic_cast<HUD*>( headUpDockWidget->widget() );
if (tmpHud)
{
}
}
this->show();
}
void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view)
......
......@@ -38,237 +38,242 @@ MapWidget::MapWidget(QWidget *parent) :
m_ui(new Ui::MapWidget)
{
m_ui->setupUi(this);
init();
}
void MapWidget::init()
{
mc = new qmapcontrol::MapControl(this->size());
if (!initialized)
{
mc = new qmapcontrol::MapControl(this->size());
// display the MapControl in the application
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
layout->setSpacing(0);
layout->addWidget(mc, 0, 0);
setLayout(layout);
// VISUAL MAP STYLE
QString buttonStyle("QAbstractButton { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)} QAbstractButton:checked { border: 2px solid #379AC3; }");
mc->setPen(QGC::colorCyan.darker(400));
// VISUAL MAP STYLE
QString buttonStyle("QAbstractButton { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)} QAbstractButton:checked { border: 2px solid #379AC3; }");
mc->setPen(QGC::colorCyan.darker(400));
waypointIsDrag = false;
waypointIsDrag = false;
// Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus);
// Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus);
// create MapControl
mc->showScale(true);
mc->showCoord(true);
mc->enablePersistentCache();
mc->setMouseTracking(true); // required to update the mouse position for diplay and capture
// create MapAdapter to get maps from
//TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17);
qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
// MAP BACKGROUND
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l = new qmapcontrol::MapLayer("Google Satellite", mapadapter);
mc->addLayer(l);
// STREET OVERLAY
overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay);
overlay->setVisible(false);
mc->addLayer(overlay);
// MAV FLIGHT TRACKS
tracks = new qmapcontrol::MapLayer("Tracking", mapadapter);
mc->addLayer(tracks);
// WAYPOINT LAYER
// create a layer with the mapadapter and type GeometryLayer (for waypoints)
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
//
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
// Zurich, ETH
int lastZoom = 16;
double lastLat = 47.376889;
double lastLon = 8.548056;
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
lastLat = settings.value("LAST_LATITUDE", lastLat).toDouble();
lastLon = settings.value("LAST_LONGITUDE", lastLon).toDouble();
lastZoom = settings.value("LAST_ZOOM", lastZoom).toInt();
settings.endGroup();
// SET INITIAL POSITION AND ZOOM
// Set default zoom level
mc->setZoom(lastZoom);
mc->setView(QPointF(lastLon, lastLat));
// Veracruz Mexico
//mc->setView(QPointF(-96.105208,19.138955));
// Add controls to select map provider
/////////////////////////////////////////////////
QActionGroup* mapproviderGroup = new QActionGroup(this);
osmAction = new QAction(QIcon(":/images/mapproviders/openstreetmap.png"), tr("OpenStreetMap"), mapproviderGroup);
yahooActionMap = new QAction(QIcon(":/images/mapproviders/yahoo.png"), tr("Yahoo: Map"), mapproviderGroup);
yahooActionSatellite = new QAction(QIcon(":/images/mapproviders/yahoo.png"), tr("Yahoo: Satellite"), mapproviderGroup);
googleActionMap = new QAction(QIcon(":/images/mapproviders/google.png"), tr("Google: Map"), mapproviderGroup);
googleSatAction = new QAction(QIcon(":/images/mapproviders/google.png"), tr("Google: Sat"), mapproviderGroup);
osmAction->setCheckable(true);
yahooActionMap->setCheckable(true);
yahooActionSatellite->setCheckable(true);
googleActionMap->setCheckable(true);
googleSatAction->setCheckable(true);
googleSatAction->setChecked(true);
connect(mapproviderGroup, SIGNAL(triggered(QAction*)),
this, SLOT(mapproviderSelected(QAction*)));
// Overlay seems currently broken
// yahooActionOverlay = new QAction(tr("Yahoo: street overlay"), this);
// yahooActionOverlay->setCheckable(true);
// yahooActionOverlay->setChecked(overlay->isVisible());
// connect(yahooActionOverlay, SIGNAL(toggled(bool)),
// overlay, SLOT(setVisible(bool)));
// mapproviderGroup->addAction(googleSatAction);
// mapproviderGroup->addAction(osmAction);
// mapproviderGroup->addAction(yahooActionOverlay);
// mapproviderGroup->addAction(googleActionMap);
// mapproviderGroup->addAction(yahooActionMap);
// mapproviderGroup->addAction(yahooActionSatellite);
// Create map provider selection menu
mapMenu = new QMenu(this);
mapMenu->addActions(mapproviderGroup->actions());
mapMenu->addSeparator();
// mapMenu->addAction(yahooActionOverlay);
mapButton = new QPushButton(this);
mapButton->setText("Map Source");
mapButton->setMenu(mapMenu);
mapButton->setStyleSheet(buttonStyle);
// display the MapControl in the application
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
layout->setSpacing(0);
layout->addWidget(mc, 0, 0);
setLayout(layout);
// create buttons to control the map (zoom, GPS tracking and WP capture)
QPushButton* zoomin = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
zoomin->setStyleSheet(buttonStyle);
QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this);
zoomout->setStyleSheet(buttonStyle);
createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this);
createPath->setStyleSheet(buttonStyle);
createPath->setToolTip(tr("Start / end waypoint add mode"));
createPath->setStatusTip(tr("Start / end waypoint add mode"));
// clearTracking = new QPushButton(QIcon(""), "", this);
// clearTracking->setStyleSheet(buttonStyle);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
followgps->setStyleSheet(buttonStyle);
followgps->setToolTip(tr("Follow the position of the current MAV with the map center"));
followgps->setStatusTip(tr("Follow the position of the current MAV with the map center"));
QPushButton* goToButton = new QPushButton(QIcon(""), "T", this);
goToButton->setStyleSheet(buttonStyle);
goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to"));
goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to"));
zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(30);
createPath->setMaximumWidth(30);
// clearTracking->setMaximumWidth(30);
followgps->setMaximumWidth(30);
goToButton->setMaximumWidth(30);
// Set checkable buttons
// TODO: Currently checked buttons are are very difficult to distinguish when checked.
// create a style and the slots to change the background so it is easier to distinguish
followgps->setCheckable(true);
createPath->setCheckable(true);
// add buttons to control the map (zoom, GPS tracking and WP capture)
QGridLayout* innerlayout = new QGridLayout(mc);
innerlayout->setMargin(3);
innerlayout->setSpacing(3);
innerlayout->addWidget(zoomin, 0, 0);
innerlayout->addWidget(zoomout, 1, 0);
innerlayout->addWidget(followgps, 2, 0);
innerlayout->addWidget(createPath, 3, 0);
//innerlayout->addWidget(clearTracking, 4, 0);
// Add spacers to compress buttons on the top left
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0);
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 0, 1, 0, 7);
innerlayout->addWidget(mapButton, 0, 6);
innerlayout->addWidget(goToButton, 0, 7);
innerlayout->setRowStretch(0, 1);
innerlayout->setRowStretch(1, 100);
mc->setLayout(innerlayout);
// Configure the WP Path's pen
pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3);
waypointPath = new qmapcontrol::LineString (wps, "Waypoint path", pointPen);
mc->layer("Waypoints")->addGeometry(waypointPath);
//Camera Control
// CAMERA INDICATOR LAYER
// create a layer with the mapadapter and type GeometryLayer (for camera indicator)
camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter);
mc->addLayer(camLayer);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
drawCamBorder = false;
radioCamera = 10;
// Done set state
initialized = true;
// Connect the required signals-slots
connect(zoomin, SIGNAL(clicked(bool)),
mc, SLOT(zoomIn()));
connect(zoomout, SIGNAL(clicked(bool)),
mc, SLOT(zoomOut()));
connect(goToButton, SIGNAL(clicked()), this, SLOT(goTo()));
QList<UASInterface*> systems = UASManager::instance()->getUASList();
foreach(UASInterface* system, systems)
{
addUAS(system);
}
// create MapControl
mc->showScale(true);
mc->showCoord(true);
mc->enablePersistentCache();
mc->setMouseTracking(true); // required to update the mouse position for diplay and capture
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
this, SLOT(addUAS(UASInterface*)));
// create MapAdapter to get maps from
//TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17);
activeUASSet(UASManager::instance()->getActiveUAS());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)),
this, SLOT(captureMapClick(const QMouseEvent*, const QPointF)));
// MAP BACKGROUND
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l = new qmapcontrol::MapLayer("Google Satellite", mapadapter);
mc->addLayer(l);
// STREET OVERLAY
overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay);
overlay->setVisible(false);
mc->addLayer(overlay);
// MAV FLIGHT TRACKS
tracks = new qmapcontrol::MapLayer("Tracking", mapadapter);
mc->addLayer(tracks);
// WAYPOINT LAYER
// create a layer with the mapadapter and type GeometryLayer (for waypoints)
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
//
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
// Zurich, ETH
int lastZoom = 16;
double lastLat = 47.376889;
double lastLon = 8.548056;
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
lastLat = settings.value("LAST_LATITUDE", lastLat).toDouble();
lastLon = settings.value("LAST_LONGITUDE", lastLon).toDouble();
lastZoom = settings.value("LAST_ZOOM", lastZoom).toInt();
settings.endGroup();
// SET INITIAL POSITION AND ZOOM
// Set default zoom level
mc->setZoom(lastZoom);
mc->setView(QPointF(lastLon, lastLat));
// Veracruz Mexico
//mc->setView(QPointF(-96.105208,19.138955));
// Add controls to select map provider
/////////////////////////////////////////////////
QActionGroup* mapproviderGroup = new QActionGroup(this);
osmAction = new QAction(QIcon(":/images/mapproviders/openstreetmap.png"), tr("OpenStreetMap"), mapproviderGroup);
yahooActionMap = new QAction(QIcon(":/images/mapproviders/yahoo.png"), tr("Yahoo: Map"), mapproviderGroup);
yahooActionSatellite = new QAction(QIcon(":/images/mapproviders/yahoo.png"), tr("Yahoo: Satellite"), mapproviderGroup);
googleActionMap = new QAction(QIcon(":/images/mapproviders/google.png"), tr("Google: Map"), mapproviderGroup);
googleSatAction = new QAction(QIcon(":/images/mapproviders/google.png"), tr("Google: Sat"), mapproviderGroup);
osmAction->setCheckable(true);
yahooActionMap->setCheckable(true);
yahooActionSatellite->setCheckable(true);
googleActionMap->setCheckable(true);
googleSatAction->setCheckable(true);
googleSatAction->setChecked(true);
connect(mapproviderGroup, SIGNAL(triggered(QAction*)),
this, SLOT(mapproviderSelected(QAction*)));
// Overlay seems currently broken
// yahooActionOverlay = new QAction(tr("Yahoo: street overlay"), this);
// yahooActionOverlay->setCheckable(true);
// yahooActionOverlay->setChecked(overlay->isVisible());
// connect(yahooActionOverlay, SIGNAL(toggled(bool)),
// overlay, SLOT(setVisible(bool)));
// mapproviderGroup->addAction(googleSatAction);
// mapproviderGroup->addAction(osmAction);
// mapproviderGroup->addAction(yahooActionOverlay);
// mapproviderGroup->addAction(googleActionMap);
// mapproviderGroup->addAction(yahooActionMap);
// mapproviderGroup->addAction(yahooActionSatellite);
// Create map provider selection menu
mapMenu = new QMenu(this);
mapMenu->addActions(mapproviderGroup->actions());
mapMenu->addSeparator();
// mapMenu->addAction(yahooActionOverlay);
mapButton = new QPushButton(this);
mapButton->setText("Map Source");
mapButton->setMenu(mapMenu);
mapButton->setStyleSheet(buttonStyle);
// create buttons to control the map (zoom, GPS tracking and WP capture)
QPushButton* zoomin = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
zoomin->setStyleSheet(buttonStyle);
QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this);
zoomout->setStyleSheet(buttonStyle);
createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this);
createPath->setStyleSheet(buttonStyle);
createPath->setToolTip(tr("Start / end waypoint add mode"));
createPath->setStatusTip(tr("Start / end waypoint add mode"));
// clearTracking = new QPushButton(QIcon(""), "", this);
// clearTracking->setStyleSheet(buttonStyle);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
followgps->setStyleSheet(buttonStyle);
followgps->setToolTip(tr("Follow the position of the current MAV with the map center"));
followgps->setStatusTip(tr("Follow the position of the current MAV with the map center"));
QPushButton* goToButton = new QPushButton(QIcon(""), "T", this);
goToButton->setStyleSheet(buttonStyle);
goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to"));
goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to"));
zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(30);
createPath->setMaximumWidth(30);
// clearTracking->setMaximumWidth(30);
followgps->setMaximumWidth(30);
goToButton->setMaximumWidth(30);
// Set checkable buttons
// TODO: Currently checked buttons are are very difficult to distinguish when checked.
// create a style and the slots to change the background so it is easier to distinguish
followgps->setCheckable(true);
createPath->setCheckable(true);
// add buttons to control the map (zoom, GPS tracking and WP capture)
QGridLayout* innerlayout = new QGridLayout(mc);
innerlayout->setMargin(3);
innerlayout->setSpacing(3);
innerlayout->addWidget(zoomin, 0, 0);
innerlayout->addWidget(zoomout, 1, 0);
innerlayout->addWidget(followgps, 2, 0);
innerlayout->addWidget(createPath, 3, 0);
//innerlayout->addWidget(clearTracking, 4, 0);
// Add spacers to compress buttons on the top left
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0);
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 0, 1, 0, 7);
innerlayout->addWidget(mapButton, 0, 6);
innerlayout->addWidget(goToButton, 0, 7);
innerlayout->setRowStretch(0, 1);
innerlayout->setRowStretch(1, 100);
mc->setLayout(innerlayout);
// Configure the WP Path's pen
pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3);
waypointPath = new qmapcontrol::LineString (wps, "Waypoint path", pointPen);
mc->layer("Waypoints")->addGeometry(waypointPath);
//Camera Control
// CAMERA INDICATOR LAYER
// create a layer with the mapadapter and type GeometryLayer (for camera indicator)
camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter);
mc->addLayer(camLayer);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
drawCamBorder = false;
radioCamera = 10;
// Done set state
initialized = true;
// Connect the required signals-slots
connect(zoomin, SIGNAL(clicked(bool)),
mc, SLOT(zoomIn()));
connect(zoomout, SIGNAL(clicked(bool)),
mc, SLOT(zoomOut()));
connect(goToButton, SIGNAL(clicked()), this, SLOT(goTo()));
QList<UASInterface*> systems = UASManager::instance()->getUASList();
foreach(UASInterface* system, systems)
{
addUAS(system);
}
connect(createPath, SIGNAL(clicked(bool)),
this, SLOT(createPathButtonClicked(bool)));
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
this, SLOT(addUAS(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)),
this, SLOT(captureGeometryClick(Geometry*, QPoint)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)),
this, SLOT(captureMapClick(const QMouseEvent*, const QPointF)));
connect(geomLayer, SIGNAL(geometryDragged(Geometry*, QPointF)),
this, SLOT(captureGeometryDrag(Geometry*, QPointF)));
connect(createPath, SIGNAL(clicked(bool)),
this, SLOT(createPathButtonClicked(bool)));
connect(geomLayer, SIGNAL(geometryEndDrag(Geometry*, QPointF)),
this, SLOT(captureGeometryEndDrag(Geometry*, QPointF)));
connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)),
this, SLOT(captureGeometryClick(Geometry*, QPoint)));
connect(geomLayer, SIGNAL(geometryDragged(Geometry*, QPointF)),
this, SLOT(captureGeometryDrag(Geometry*, QPointF)));
connect(geomLayer, SIGNAL(geometryEndDrag(Geometry*, QPointF)),
this, SLOT(captureGeometryEndDrag(Geometry*, QPointF)));
qDebug() << "CHECK END";
}
}
void MapWidget::goTo()
......@@ -299,118 +304,123 @@ void MapWidget::goTo()
void MapWidget::mapproviderSelected(QAction* action)
{
//delete mapadapter;
mapButton->setText(action->text());
if (action == osmAction)
if (mc)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::OSMMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == yahooActionMap)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::YahooMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == yahooActionSatellite)
{
int zoom = mapadapter->adaptedZoom();
QPointF a = mc->currentCoordinate();
mc->setZoom(0);
//delete mapadapter;
mapButton->setText(action->text());
if (action == osmAction)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
mapadapter = new qmapcontrol::OSMMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
overlay->setVisible(false);
// yahooActionOverlay->setEnabled(true);
}
else if (action == googleActionMap)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::GoogleMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == googleSatAction)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else
{
mapButton->setText("Select..");
}
else if (action == yahooActionMap)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::YahooMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == yahooActionSatellite)
{
int zoom = mapadapter->adaptedZoom();
QPointF a = mc->currentCoordinate();
mc->setZoom(0);
mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
overlay->setVisible(false);
// yahooActionOverlay->setEnabled(true);
}
else if (action == googleActionMap)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::GoogleMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == googleSatAction)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
if (isVisible()) mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
}
else
{
mapButton->setText("Select..");
}
}
}
void MapWidget::createPathButtonClicked(bool checked)
{
Q_UNUSED(checked);
if (createPath->isChecked())
if (mc)
{
// change the cursor shape
this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None);
Q_UNUSED(checked);
if (createPath->isChecked())
{
// change the cursor shape
this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None);
// emit signal start to create a Waypoint global
//emit createGlobalWP(true, mc->currentCoordinate());
// // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog
// mc->layer("Waypoints")->clearGeometries();
// wps.clear();
// path->setPoints(wps);
// mc->layer("Waypoints")->addGeometry(path);
// wpIndex.clear();
}
else
{
// emit signal start to create a Waypoint global
//emit createGlobalWP(true, mc->currentCoordinate());
this->setCursor(Qt::ArrowCursor);
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
// // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog
// mc->layer("Waypoints")->clearGeometries();
// wps.clear();
// path->setPoints(wps);
// mc->layer("Waypoints")->addGeometry(path);
// wpIndex.clear();
}
else
{
this->setCursor(Qt::ArrowCursor);
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
}
}
/**
......@@ -476,79 +486,82 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp)
*/
void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
{
// Make sure this is the right UAS
if (uas == this->mav->getUASID())
if (mc)
{
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL)
// Make sure this is the right UAS
if (uas == this->mav->getUASID())
{
// We're good, this is a global waypoint
// Only accept waypoints in global coordinate frame
if (wp->getFrame() == MAV_FRAME_GLOBAL)
{
// We're good, this is a global waypoint
// Get the index of this waypoint
// note the call to getGlobalFrameIndexOf()
// as we're only handling global waypoints
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1) return;
// Get the index of this waypoint
// note the call to getGlobalFrameIndexOf()
// as we're only handling global waypoints
int wpindex = UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameIndexOf(wp);
// If not found, return (this should never happen, but helps safety)
if (wpindex == -1) return;
// Check if wp exists yet in map
if (!(wpIcons.count() > wpindex))
{
// Waypoint is new, a new icon is created
QPointF coordinate;
coordinate.setX(wp->getLongitude());
coordinate.setY(wp->getLatitude());
createWaypointGraphAtMap(wpindex, coordinate);
}
else
{
// Waypoint exists, update it if we're not
// currently dragging it with the mouse
if(!waypointIsDrag)
// Check if wp exists yet in map
if (!(wpIcons.count() > wpindex))
{
// Waypoint is new, a new icon is created
QPointF coordinate;
coordinate.setX(wp->getLongitude());
coordinate.setY(wp->getLatitude());
Point* waypoint;
waypoint = wps.at(wpindex);
if (waypoint)
createWaypointGraphAtMap(wpindex, coordinate);
}
else
{
// Waypoint exists, update it if we're not
// currently dragging it with the mouse
if(!waypointIsDrag)
{
// First set waypoint coordinate
waypoint->setCoordinate(coordinate);
// Now update icon position
wpIcons.at(wpindex)->setCoordinate(coordinate);
// Update pen
wpIcons.at(wpindex)->setPen(mavPens.value(uas));
// Then waypoint line coordinate
Point* linesegment = NULL;
// If the line segment already exists, just update it
// else create a new one
if (waypointPath->points().size() > wpindex)
{
linesegment = waypointPath->points().at(wpindex);
if (linesegment) linesegment->setCoordinate(coordinate);
}
else
QPointF coordinate;
coordinate.setX(wp->getLongitude());
coordinate.setY(wp->getLatitude());
Point* waypoint;
waypoint = wps.at(wpindex);
if (waypoint)
{
waypointPath->addPoint(waypoint);
// First set waypoint coordinate
waypoint->setCoordinate(coordinate);
// Now update icon position
wpIcons.at(wpindex)->setCoordinate(coordinate);
// Update pen
wpIcons.at(wpindex)->setPen(mavPens.value(uas));
// Then waypoint line coordinate
Point* linesegment = NULL;
// If the line segment already exists, just update it
// else create a new one
if (waypointPath->points().size() > wpindex)
{
linesegment = waypointPath->points().at(wpindex);
if (linesegment) linesegment->setCoordinate(coordinate);
}
else
{
waypointPath->addPoint(waypoint);
}
// Update view
if (updateView) if (isVisible()) mc->updateRequest(waypoint->boundingBox().toRect());
}
// Update view
if (updateView) if (isVisible()) mc->updateRequest(waypoint->boundingBox().toRect());
}
}
}
}
else
{
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
else
{
updateWaypointList(uas);
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
{
updateWaypointList(uas);
}
}
}
}
......@@ -599,11 +612,14 @@ void MapWidget::createWaypointGraphAtMap(int id, const QPointF coordinate)
int MapWidget::wpExists(const QPointF coordinate)
{
for (int i = 0; i < wps.size(); i++){
if (wps.at(i)->latitude() == coordinate.y() &&
wps.at(i)->longitude()== coordinate.x())
{
return 1;
if (mc)
{
for (int i = 0; i < wps.size(); i++){
if (wps.at(i)->latitude() == coordinate.y() &&
wps.at(i)->longitude()== coordinate.x())
{
return 1;
}
}
}
return 0;
......@@ -615,7 +631,7 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
Q_UNUSED(geom);
Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None);
if (mc) mc->setMouseMode(qmapcontrol::MapControl::None);
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
......@@ -680,6 +696,7 @@ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
MapWidget::~MapWidget()
{
delete mc;
delete m_ui;
}
/**
......@@ -700,51 +717,54 @@ void MapWidget::addUAS(UASInterface* uas)
*/
void MapWidget::updateWaypointList(int uas)
{
// Get already existing waypoints
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (uasInstance)
if (mc)
{
// Get update rect of old content, this is what will be redrawn
// in the last step
QRect updateRect = waypointPath->boundingBox().toRect();
// Get already existing waypoints
UASInterface* uasInstance = UASManager::instance()->getUASForId(uas);
if (uasInstance)
{
// Get update rect of old content, this is what will be redrawn
// in the last step
QRect updateRect = waypointPath->boundingBox().toRect();
// Get all waypoints, including non-global waypoints
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getWaypointList();
// Get all waypoints, including non-global waypoints
QVector<Waypoint*> wpList = uasInstance->getWaypointManager()->getWaypointList();
// Clear if necessary
if (wpList.count() == 0)
{
clearWaypoints(uas);
return;
}
// Clear if necessary
if (wpList.count() == 0)
{
clearWaypoints(uas);
return;
}
// Trim internal list to number of global waypoints in the waypoint manager list
int overSize = waypointPath->points().count() - uasInstance->getWaypointManager()->getGlobalFrameCount();
if (overSize > 0)
{
// Remove n waypoints at the end of the list
// the remaining waypoints will be updated
// in the next step
for (int i = 0; i < overSize; ++i)
// Trim internal list to number of global waypoints in the waypoint manager list
int overSize = waypointPath->points().count() - uasInstance->getWaypointManager()->getGlobalFrameCount();
if (overSize > 0)
{
wps.removeLast();
mc->layer("Waypoints")->removeGeometry(wpIcons.last());
wpIcons.removeLast();
waypointPath->points().removeLast();
// Remove n waypoints at the end of the list
// the remaining waypoints will be updated
// in the next step
for (int i = 0; i < overSize; ++i)
{
wps.removeLast();
mc->layer("Waypoints")->removeGeometry(wpIcons.last());
wpIcons.removeLast();
waypointPath->points().removeLast();
}
}
}
// Load all existing waypoints into map view
foreach (Waypoint* wp, wpList)
{
// Block map draw updates, since we update everything in the next step
// but update internal data structures.
// Please note that updateWaypoint() ignores non-global waypoints
updateWaypoint(mav->getUASID(), wp, false);
}
// Load all existing waypoints into map view
foreach (Waypoint* wp, wpList)
{
// Block map draw updates, since we update everything in the next step
// but update internal data structures.
// Please note that updateWaypoint() ignores non-global waypoints
updateWaypoint(mav->getUASID(), wp, false);
}
// Update view
if (isVisible()) mc->updateRequest(updateRect);
// Update view
if (isVisible()) mc->updateRequest(updateRect);
}
}
}
......@@ -776,7 +796,7 @@ void MapWidget::activeUASSet(UASInterface* uas)
disconnect(this, SIGNAL(waypointCreated(Waypoint*)), mav->getWaypointManager(), SLOT(addWaypoint(Waypoint*)));
}
if (uas)
if (uas && mc)
{
mav = uas;
QColor color = mav->getColor();
......@@ -804,27 +824,33 @@ void MapWidget::activeUASSet(UASInterface* uas)
void MapWidget::updateSystemSpecs(int uas)
{
foreach (qmapcontrol::Point* p, uasIcons.values())
if (mc)
{
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
if (icon && icon->getUASId() == uas)
foreach (qmapcontrol::Point* p, uasIcons.values())
{
// Set new airframe
icon->setAirframe(UASManager::instance()->getUASForId(uas)->getAirframe());
icon->drawIcon();
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
if (icon && icon->getUASId() == uas)
{
// Set new airframe
icon->setAirframe(UASManager::instance()->getUASForId(uas)->getAirframe());
icon->drawIcon();
}
}
}
}
void MapWidget::updateSelectedSystem(int uas)
{
foreach (qmapcontrol::Point* p, uasIcons.values())
if (mc)
{
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
if (icon)
foreach (qmapcontrol::Point* p, uasIcons.values())
{
// Set as selected if ids match
icon->setSelectedUAS((icon->getUASId() == uas));
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(p);
if (icon)
{
// Set as selected if ids match
icon->setSelectedUAS((icon->getUASId() == uas));
}
}
}
}
......@@ -834,13 +860,16 @@ void MapWidget::updateAttitude(UASInterface* uas, double roll, double pitch, dou
Q_UNUSED(roll);
Q_UNUSED(pitch);
Q_UNUSED(usec);
if (uas)
if (mc)
{
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID(), NULL));
if (icon)
if (uas)
{
icon->setYaw(yaw);
MAV2DIcon* icon = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID(), NULL));
if (icon)
{
icon->setYaw(yaw);
}
}
}
}
......@@ -858,79 +887,81 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
{
Q_UNUSED(usec);
Q_UNUSED(alt); // FIXME Use altitude
// create a LineString
//QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
qmapcontrol::Point* p;
QPointF coordinate;
coordinate.setX(lon);
coordinate.setY(lat);
if (!uasIcons.contains(uas->getUASID()))
if (mc)
{
// Get the UAS color
QColor uasColor = uas->getColor();
// Icon
//QPen* pointpen = new QPen(uasColor);
qDebug() << "2D MAP: ADDING" << uas->getUASName() << __FILE__ << __LINE__;
p = new MAV2DIcon(uas, 68, uas->getSystemType(), uas->getColor(), QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
uasIcons.insert(uas->getUASID(), p);
mc->layer("Waypoints")->addGeometry(p);
// Line
// A QPen also can use transparency
// QList<qmapcontrol::Point*> points;
// points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// QPen* linepen = new QPen(uasColor.darker());
// linepen->setWidth(2);
// // Create tracking line string
// qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
// uasTrails.insert(uas->getUASID(), ls);
// // Add the LineString to the layer
// mc->layer("Waypoints")->addGeometry(ls);
}
else
{
// p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
// if (p)
// {
p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lon, lat));
//p->setYaw(uas->getYaw());
// }
// Extend trail
// uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
}
// create a LineString
//QList<Point*> points;
// Points with a circle
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
qmapcontrol::Point* p;
QPointF coordinate;
coordinate.setX(lon);
coordinate.setY(lat);
if (!uasIcons.contains(uas->getUASID()))
{
// Get the UAS color
QColor uasColor = uas->getColor();
// Icon
//QPen* pointpen = new QPen(uasColor);
qDebug() << "2D MAP: ADDING" << uas->getUASName() << __FILE__ << __LINE__;
p = new MAV2DIcon(uas, 68, uas->getSystemType(), uas->getColor(), QString("%1").arg(uas->getUASID()), qmapcontrol::Point::Middle);
uasIcons.insert(uas->getUASID(), p);
mc->layer("Waypoints")->addGeometry(p);
// Line
// A QPen also can use transparency
// QList<qmapcontrol::Point*> points;
// points.append(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
// QPen* linepen = new QPen(uasColor.darker());
// linepen->setWidth(2);
// // Create tracking line string
// qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, QString("%1").arg(uas->getUASID()), linepen);
// uasTrails.insert(uas->getUASID(), ls);
// // Add the LineString to the layer
// mc->layer("Waypoints")->addGeometry(ls);
}
else
{
// p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
// if (p)
// {
p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lon, lat));
//p->setYaw(uas->getYaw());
// }
// Extend trail
// uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(coordinate.x(), coordinate.y()));
}
if (isVisible()) mc->updateRequest(p->boundingBox().toRect());
if (isVisible()) mc->updateRequest(p->boundingBox().toRect());
//if (isVisible()) mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());
//if (isVisible()) mc->updateRequestNew();//(uasTrails.value(uas->getUASID())->boundingBox().toRect());
if (this->mav && uas->getUASID() == this->mav->getUASID())
{
// Limit the position update rate
quint64 currTime = MG::TIME::getGroundTimeNow();
if (currTime - lastUpdate > 120)
if (this->mav && uas->getUASID() == this->mav->getUASID())
{
lastUpdate = currTime;
// Sets the view to the interesting area
if (followgps->isChecked())
{
updatePosition(0, lon, lat);
}
else
// Limit the position update rate
quint64 currTime = MG::TIME::getGroundTimeNow();
if (currTime - lastUpdate > 120)
{
// Refresh the screen
//if (isVisible()) mc->updateRequestNew();
lastUpdate = currTime;
// Sets the view to the interesting area
if (followgps->isChecked())
{
updatePosition(0, lon, lat);
}
else
{
// Refresh the screen
//if (isVisible()) mc->updateRequestNew();
}
}
}
}
......@@ -943,7 +974,7 @@ void MapWidget::updatePosition(float time, double lat, double lon)
{
Q_UNUSED(time);
//gpsposition->setText(QString::number(time) + " / " + QString::number(lat) + " / " + QString::number(lon));
if (followgps->isChecked() && isVisible())
if (followgps->isChecked() && isVisible() && mc)
{
if (mc) mc->setView(QPointF(lat, lon));
}
......@@ -951,79 +982,88 @@ void MapWidget::updatePosition(float time, double lat, double lon)
void MapWidget::wheelEvent(QWheelEvent *event)
{
int numDegrees = event->delta() / 8;
int numSteps = numDegrees / 15;
// Calculate new zoom level
int newZoom = mc->currentZoom()+numSteps;
// Set new zoom level, level is bounded by map control
mc->setZoom(newZoom);
// Detail zoom level is the number of steps zoomed in further
// after the bounding has taken effect
detailZoom = qAbs(qMin(0, mc->currentZoom()-newZoom));
// visual field of camera
updateCameraPosition(20*newZoom,0,"no");
if (mc)
{
int numDegrees = event->delta() / 8;
int numSteps = numDegrees / 15;
// Calculate new zoom level
int newZoom = mc->currentZoom()+numSteps;
// Set new zoom level, level is bounded by map control
mc->setZoom(newZoom);
// Detail zoom level is the number of steps zoomed in further
// after the bounding has taken effect
detailZoom = qAbs(qMin(0, mc->currentZoom()-newZoom));
// visual field of camera
updateCameraPosition(20*newZoom,0,"no");
}
}
void MapWidget::keyPressEvent(QKeyEvent *event)
{
if (mc)
{
switch (event->key()) {
case Qt::Key_Plus:
mc->zoomIn();
break;
case Qt::Key_Minus:
mc->zoomOut();
break;
case Qt::Key_Left:
mc->scrollLeft(this->width()/scrollStep);
break;
case Qt::Key_Right:
mc->scrollRight(this->width()/scrollStep);
break;
case Qt::Key_Down:
mc->scrollDown(this->width()/scrollStep);
break;
case Qt::Key_Up:
mc->scrollUp(this->width()/scrollStep);
break;
default:
QWidget::keyPressEvent(event);
if (mc)
{
switch (event->key()) {
case Qt::Key_Plus:
mc->zoomIn();
break;
case Qt::Key_Minus:
mc->zoomOut();
break;
case Qt::Key_Left:
mc->scrollLeft(this->width()/scrollStep);
break;
case Qt::Key_Right:
mc->scrollRight(this->width()/scrollStep);
break;
case Qt::Key_Down:
mc->scrollDown(this->width()/scrollStep);
break;
case Qt::Key_Up:
mc->scrollUp(this->width()/scrollStep);
break;
default:
QWidget::keyPressEvent(event);
}
}
}
}
void MapWidget::resizeEvent(QResizeEvent* event )
{
Q_UNUSED(event);
if (!initialized)
{
init();
}
if (mc) mc->resize(this->size());
}
void MapWidget::showEvent(QShowEvent* event)
{
Q_UNUSED(event);
if (!initialized)
{
initialized = true;
init();
}
// if (isVisible())
// {
// if (!initialized)
// {
// init();
// }
// }
}
void MapWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
QPointF currentPos = mc->currentCoordinate();
settings.setValue("LAST_LATITUDE", currentPos.y());
settings.setValue("LAST_LONGITUDE", currentPos.x());
settings.setValue("LAST_ZOOM", mc->currentZoom());
settings.endGroup();
settings.sync();
if (!initialized) init();
if (mc)
{
QSettings settings;
settings.beginGroup("QGC_MAPWIDGET");
QPointF currentPos = mc->currentCoordinate();
settings.setValue("LAST_LATITUDE", currentPos.y());
settings.setValue("LAST_LONGITUDE", currentPos.x());
settings.setValue("LAST_ZOOM", mc->currentZoom());
settings.endGroup();
settings.sync();
}
}
......@@ -1041,98 +1081,103 @@ void MapWidget::changeEvent(QEvent *e)
void MapWidget::clearWaypoints(int uas)
{
Q_UNUSED(uas);
// Clear the previous WP track
//mc->layer("Waypoints")->clearGeometries();
wps.clear();
foreach (Point* p, wpIcons)
if (mc)
{
mc->layer("Waypoints")->removeGeometry(p);
}
wpIcons.clear();
Q_UNUSED(uas);
// Clear the previous WP track
// Get bounding box of this object BEFORE deleting the content
QRect box = waypointPath->boundingBox().toRect();
//mc->layer("Waypoints")->clearGeometries();
wps.clear();
foreach (Point* p, wpIcons)
{
mc->layer("Waypoints")->removeGeometry(p);
}
wpIcons.clear();
// Delete the content
waypointPath->points().clear();
// Get bounding box of this object BEFORE deleting the content
QRect box = waypointPath->boundingBox().toRect();
//delete waypointPath;
//waypointPath = new
//mc->layer("Waypoints")->addGeometry(waypointPath);
//wpIndex.clear();
if (isVisible()) mc->updateRequest(box);//(waypointPath->boundingBox().toRect());
// Delete the content
waypointPath->points().clear();
if(createPath->isChecked())
{
createPath->click();
}
//delete waypointPath;
//waypointPath = new
//mc->layer("Waypoints")->addGeometry(waypointPath);
//wpIndex.clear();
if (isVisible()) mc->updateRequest(box);//(waypointPath->boundingBox().toRect());
qDebug() << "CLEARING WAYPOINTS";
if(createPath->isChecked())
{
createPath->click();
}
}
}
void MapWidget::clearPath(int uas)
{
Q_UNUSED(uas);
mc->layer("Tracking")->clearGeometries();
foreach (qmapcontrol::LineString* ls, uasTrails)
if (mc)
{
QPen* linepen = ls->pen();
delete ls;
qmapcontrol::LineString* lsNew = new qmapcontrol::LineString(QList<qmapcontrol::Point*>(), "", linepen);
mc->layer("Tracking")->addGeometry(lsNew);
mc->layer("Tracking")->clearGeometries();
foreach (qmapcontrol::LineString* ls, uasTrails)
{
QPen* linepen = ls->pen();
delete ls;
qmapcontrol::LineString* lsNew = new qmapcontrol::LineString(QList<qmapcontrol::Point*>(), "", linepen);
mc->layer("Tracking")->addGeometry(lsNew);
}
// FIXME update this with update request only for bounding box of trails
if (isVisible()) mc->updateRequestNew();//(QRect(0, 0, width(), height()));
}
// FIXME update this with update request only for bounding box of trails
if (isVisible()) mc->updateRequestNew();//(QRect(0, 0, width(), height()));
}
void MapWidget::updateCameraPosition(double radio, double bearing, QString dir)
{
Q_UNUSED(dir);
Q_UNUSED(bearing);
// FIXME Mariano
//camPoints.clear();
QPointF currentPos = mc->currentCoordinate();
// QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance);
if (mc)
{
// FIXME Mariano
//camPoints.clear();
QPointF currentPos = mc->currentCoordinate();
// QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance);
// qmapcontrol::Point* tempPoint1 = new qmapcontrol::Point(currentPos.x(), currentPos.y(),"inicial",qmapcontrol::Point::Middle);
// qmapcontrol::Point* tempPoint2 = new qmapcontrol::Point(actualPos.x(), actualPos.y(),"final",qmapcontrol::Point::Middle);
// qmapcontrol::Point* tempPoint1 = new qmapcontrol::Point(currentPos.x(), currentPos.y(),"inicial",qmapcontrol::Point::Middle);
// qmapcontrol::Point* tempPoint2 = new qmapcontrol::Point(actualPos.x(), actualPos.y(),"final",qmapcontrol::Point::Middle);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camLine->setPoints(camPoints);
// camLine->setPoints(camPoints);
QPen* camBorderPen = new QPen(QColor(255,0,0));
camBorderPen->setWidth(2);
QPen* camBorderPen = new QPen(QColor(255,0,0));
camBorderPen->setWidth(2);
//radio = mc->currentZoom()
//radio = mc->currentZoom()
if(drawCamBorder)
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
if(drawCamBorder)
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
//create a camera borders
qmapcontrol::CirclePoint* camBorder = new qmapcontrol::CirclePoint(currentPos.x(), currentPos.y(), radio, "camBorder", qmapcontrol::Point::Middle, camBorderPen);
//create a camera borders
qmapcontrol::CirclePoint* camBorder = new qmapcontrol::CirclePoint(currentPos.x(), currentPos.y(), radio, "camBorder", qmapcontrol::Point::Middle, camBorderPen);
//camBorder->setCoordinate(currentPos);
//camBorder->setCoordinate(currentPos);
mc->layer("Camera")->addGeometry(camBorder);
// mc->layer("Camera")->addGeometry(camLine);
if (isVisible()) mc->updateRequestNew();
mc->layer("Camera")->addGeometry(camBorder);
// mc->layer("Camera")->addGeometry(camLine);
if (isVisible()) mc->updateRequestNew();
}
else
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
if (isVisible()) mc->updateRequestNew();
}
else
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
if (isVisible()) mc->updateRequestNew();
}
}
}
void MapWidget::drawBorderCamAtMap(bool status)
......
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