Browse Source

Fixed a whole bunch of compile warnings

QGC4.4
pixhawk 15 years ago
parent
commit
16a68ab53b
  1. 7
      lib/QMapControl/src/layer.cpp
  2. 1
      src/Core.cc
  3. 4
      src/comm/MAVLinkXMLParser.cc
  4. 5
      src/uas/UASWaypointManager.cc
  5. 537
      src/ui/MapWidget.cc
  6. 2
      src/ui/SlugsPIDControl.cpp
  7. 5
      src/ui/SlugsPadCameraControl.cpp
  8. 4
      src/ui/map3D/Imagery.cc
  9. 2
      src/ui/map3D/Pixhawk3DWidget.cc
  10. 7
      src/ui/map3D/PixhawkCheetahGeode.cc
  11. 4
      src/ui/map3D/WaypointGroupNode.cc
  12. 1
      src/ui/uas/UASView.cc

7
lib/QMapControl/src/layer.cpp

@ -99,9 +99,10 @@ namespace qmapcontrol @@ -99,9 +99,10 @@ namespace qmapcontrol
Geometry* Layer::get_Geometry(int index)
{
Geometry* geo = NULL;
if(geometrySelected)
{
return geometrySelected;
geo = geometrySelected;
}
else
{
@ -110,7 +111,7 @@ namespace qmapcontrol @@ -110,7 +111,7 @@ namespace qmapcontrol
Geometry *geometry = geometries[i];
if(geometry->name() == QString::number(index))
{
return geometry;
geo = geometry;
}
}
@ -124,7 +125,7 @@ namespace qmapcontrol @@ -124,7 +125,7 @@ namespace qmapcontrol
// }
}
return geo;
}
bool Layer::isVisible() const

1
src/Core.cc

@ -122,6 +122,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) @@ -122,6 +122,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
simulationLink->disconnect();
//mainWindow->addLink(simulationLink);
mainWindow = MainWindow::instance();

4
src/comm/MAVLinkXMLParser.cc

@ -496,7 +496,7 @@ bool MAVLinkXMLParser::generate() @@ -496,7 +496,7 @@ bool MAVLinkXMLParser::generate()
if (fieldType == "uint8_t_mavlink_version")
{
unpackingCode = QString("\treturn %1;").arg(mavlinkVersion);
unpackingCode = QString("\treturn (%1)(msg->payload%2)[0];").arg("uint8_t", prepends);
}
else if (fieldType == "uint8_t" || fieldType == "int8_t")
{
@ -531,7 +531,7 @@ bool MAVLinkXMLParser::generate() @@ -531,7 +531,7 @@ bool MAVLinkXMLParser::generate()
// Generate the message decoding function
if (fieldType.contains("uint8_t_mavlink_version"))
{
unpacking += unpackingComment + QString("static inline uint8_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg)\n{\n\treturn %3;\n}\n\n").arg(messageName, fieldName).arg(mavlinkVersion);
unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg("uint8_t", messageName, fieldName, unpackingCode);
decodeLines += "";
prepends += "+sizeof(uint8_t)";
}

5
src/uas/UASWaypointManager.cc

@ -394,11 +394,14 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) @@ -394,11 +394,14 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
{
// FIXME Will be removed
Q_UNUSED(wp);
}
int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
{
// FIXME Will be removed
Q_UNUSED(seq);
return 0;
}

537
src/ui/MapWidget.cc

@ -1,5 +1,4 @@ @@ -1,5 +1,4 @@
/*=====================================================================
/*==================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project @@ -10,15 +9,15 @@ This file is part of the QGROUNDCONTROL project
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.
QGROUNDCONTROL 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 QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
@ -53,54 +52,54 @@ MapWidget::MapWidget(QWidget *parent) : @@ -53,54 +52,54 @@ MapWidget::MapWidget(QWidget *parent) :
m_ui(new Ui::MapWidget)
{
m_ui->setupUi(this);
waypointIsDrag = false;
// Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus);
// create MapControl
mc = new qmapcontrol::MapControl(QSize(320, 240));
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);
// 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);
//
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
// SET INITIAL POSITION AND ZOOM
// Set default zoom level
mc->setZoom(16);
// Zurich, ETH
//mc->setView(QPointF(8.548056,47.376389));
// Veracruz Mexico, ETH
mc->setView(QPointF(-96.105208,19.138955));
// Add controls to select map provider
/////////////////////////////////////////////////
QActionGroup* mapproviderGroup = new QActionGroup(this);
@ -117,31 +116,31 @@ MapWidget::MapWidget(QWidget *parent) : @@ -117,31 +116,31 @@ MapWidget::MapWidget(QWidget *parent) :
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);
// 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);
// mapMenu->addAction(yahooActionOverlay);
mapButton = new QPushButton(this);
mapButton->setText("Map Source");
mapButton->setMenu(mapMenu);
// display the MapControl in the application
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
@ -154,24 +153,24 @@ MapWidget::MapWidget(QWidget *parent) : @@ -154,24 +153,24 @@ MapWidget::MapWidget(QWidget *parent) :
layout->setColumnStretch(0, 1);
layout->setColumnStretch(1, 50);
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);
QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this);
createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
zoomin->setMaximumWidth(50);
zoomout->setMaximumWidth(50);
createPath->setMaximumWidth(50);
followgps->setMaximumWidth(50);
// 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(5);
@ -186,55 +185,55 @@ MapWidget::MapWidget(QWidget *parent) : @@ -186,55 +185,55 @@ MapWidget::MapWidget(QWidget *parent) :
innerlayout->setRowStretch(0, 1);
innerlayout->setRowStretch(1, 100);
mc->setLayout(innerlayout);
// Connect the required signals-slots
connect(zoomin, SIGNAL(clicked(bool)),
mc, SLOT(zoomIn()));
connect(zoomout, SIGNAL(clicked(bool)),
mc, SLOT(zoomOut()));
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
this, SLOT(addUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)),
this, SLOT(captureMapClick(const QMouseEvent*, const QPointF)));
connect(createPath, SIGNAL(clicked(bool)),
this, SLOT(createPathButtonClicked(bool)));
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)));
// Configure the WP Path's pen
pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3);
path = new qmapcontrol::LineString (wps, "UAV Path", pointPen);
mc->layer("Waypoints")->addGeometry(path);
//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;
this->setVisible(false);
}
@ -247,45 +246,45 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -247,45 +246,45 @@ void MapWidget::mapproviderSelected(QAction* action)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new qmapcontrol::OSMMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(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);
mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(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);
mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(true);
// yahooActionOverlay->setEnabled(true);
}
else if (action == googleActionMap)
{
@ -294,12 +293,12 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -294,12 +293,12 @@ void MapWidget::mapproviderSelected(QAction* action)
mapadapter = new qmapcontrol::GoogleMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
// yahooActionOverlay->setChecked(false);
}
else if (action == googleSatAction)
{
@ -308,12 +307,12 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -308,12 +307,12 @@ void MapWidget::mapproviderSelected(QAction* action)
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
mc->updateRequestNew();
mc->setZoom(zoom);
// yahooActionOverlay->setEnabled(false);
// yahooActionOverlay->setEnabled(false);
overlay->setVisible(false);
// yahooActionOverlay->setChecked(false);
// yahooActionOverlay->setChecked(false);
}
else
{
@ -324,37 +323,37 @@ void MapWidget::mapproviderSelected(QAction* action) @@ -324,37 +323,37 @@ void MapWidget::mapproviderSelected(QAction* action)
void MapWidget::createPathButtonClicked(bool checked)
{
Q_UNUSED(checked);
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();
// // 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);
}
}
/**
@ -367,146 +366,148 @@ void MapWidget::createPathButtonClicked(bool checked) @@ -367,146 +366,148 @@ void MapWidget::createPathButtonClicked(bool checked)
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate)
{
qDebug() << mc->mouseMode();
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
qDebug() << mc->mouseMode();
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
{
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
// Refresh the screen
mc->updateRequestNew();
// emit signal mouse was clicked
emit captureMapCoordinateClick(coordinate);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
// Refresh the screen
mc->updateRequestNew();
// emit signal mouse was clicked
emit captureMapCoordinateClick(coordinate);
}
}
void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
{
if (!wpExists(coordinate)){
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
//CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
if (!wpExists(coordinate)){
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
//CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
qDebug()<<"Funcion createWaypointGraphAtMap WP= "<<str<<" -> x= "<<tempPoint->latitude()<<" y= "<<tempPoint->longitude();
// Refresh the screen
mc->updateRequestNew();
}
//// // emit signal mouse was clicked
// emit captureMapCoordinateClick(coordinate);
mc->updateRequestNew();
}
//// // emit signal mouse was clicked
// emit captureMapCoordinateClick(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;
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;
return 0;
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
{
Q_UNUSED(geom);
Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None);
Q_UNUSED(geom);
Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None);
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
{
waypointIsDrag = true;
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
qmapcontrol::Point* point2Find;
point2Find = wpIndex[geom->name()];
if (point2Find)
{
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <qmapcontrol::Point*> (geom);
if (point2Find)
{
point2Find->setCoordinate(coordinate);
// qDebug() << geom->name();
temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
}
}
waypointIsDrag = true;
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
qmapcontrol::Point* point2Find;
point2Find = wpIndex[geom->name()];
if (point2Find)
{
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <qmapcontrol::Point*> (geom);
if (point2Find)
{
point2Find->setCoordinate(coordinate);
// qDebug() << geom->name();
temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
}
}
}
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{
// TODO: Investigate why when creating the waypoint path this slot is being called
// Only change the mouse mode back to panning when not creating a WP path
if (!createPath->isChecked()){
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
Q_UNUSED(geom);
Q_UNUSED(coordinate);
// TODO: Investigate why when creating the waypoint path this slot is being called
// Only change the mouse mode back to panning when not creating a WP path
if (!createPath->isChecked())
{
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
}
MapWidget::~MapWidget()
@ -554,22 +555,22 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, @@ -554,22 +555,22 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// A QPen can be used to customize the
//pointpen->setWidth(3);
//points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen));
if (!uasIcons.contains(uas->getUASID()))
{
// Get the UAS color
QColor uasColor = uas->getColor();
// Icon
QPen* pointpen = new QPen(uasColor);
qDebug() << uas->getUASName();
MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
geomLayer->addGeometry(p);
// Line
// A QPen also can use transparency
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QPen* linepen = new QPen(uasColor.darker());
@ -577,7 +578,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, @@ -577,7 +578,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Add the Points and the QPen to a LineString
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
geomLayer->addGeometry(ls);
}
@ -592,12 +593,12 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, @@ -592,12 +593,12 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
}
// Connect click events of the layer to this object
// connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)),
// this, SLOT(geometryClicked(Geometry*, QPoint)));
// Sets the view to the interesting area
updatePosition(0, lat, lon);
}
@ -627,10 +628,10 @@ void MapWidget::wheelEvent(QWheelEvent *event) @@ -627,10 +628,10 @@ void MapWidget::wheelEvent(QWheelEvent *event)
// 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");
updateCameraPosition(20*newZoom,0,"no");
}
void MapWidget::keyPressEvent(QKeyEvent *event)
@ -680,20 +681,20 @@ void MapWidget::changeEvent(QEvent *e) @@ -680,20 +681,20 @@ void MapWidget::changeEvent(QEvent *e)
void MapWidget::clearPath()
{
// Clear the previous WP track
mc->layer("Waypoints")->clearGeometries();
wps.clear();
path->setPoints(wps);
mc->layer("Waypoints")->addGeometry(path);
wpIndex.clear();
mc->updateRequestNew();
if(createPath->isChecked())
{
createPath->click();
}
}
void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon)
@ -701,87 +702,87 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa @@ -701,87 +702,87 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa
if(!waypointIsDrag)
{
qDebug() <<"indice WP= "<<index <<"\n";
QPointF coordinate;
coordinate.setX(lon);
coordinate.setY(lat);
Point* point2Find;
point2Find = wpIndex[QString::number(index)];
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <Point*> (mc->layer("Waypoints")->get_Geometry(index));
point2Find->setCoordinate(coordinate);
// Refresh the screen
mc->updateRequestNew();
}
}
}
void MapWidget::updateCameraPosition(double radio, double bearing, QString dir)
{
//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);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camLine->setPoints(camPoints);
QPen* camBorderPen = new QPen(QColor(255,0,0));
// 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);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camLine->setPoints(camPoints);
QPen* camBorderPen = new QPen(QColor(255,0,0));
camBorderPen->setWidth(2);
//radio = mc->currentZoom()
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);
//camBorder->setCoordinate(currentPos);
//camBorder->setCoordinate(currentPos);
mc->layer("Camera")->addGeometry(camBorder);
// mc->layer("Camera")->addGeometry(camLine);
// mc->layer("Camera")->addGeometry(camLine);
mc->updateRequestNew();
}
else
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
mc->updateRequestNew();
}
else
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
mc->updateRequestNew();
}
}
void MapWidget::drawBorderCamAtMap(bool status)
{
drawCamBorder = status;
updateCameraPosition(20,0,"no");
}
QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double bearing, double distance)
{
QPointF temp;
double rad = M_PI/180;
bearing = bearing*rad;
temp.setX((lon1 + ((distance/60) * (sin(bearing)))));
temp.setY((lat1 + ((distance/60) * (cos(bearing)))));
return temp;
}

2
src/ui/SlugsPIDControl.cpp

@ -640,6 +640,8 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype) @@ -640,6 +640,8 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
#else
Q_UNUSED(PIDtype);
#endif // MAVLINK_ENABLED_SLUG
}

5
src/ui/SlugsPadCameraControl.cpp

@ -221,7 +221,8 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2) @@ -221,7 +221,8 @@ double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
*/
QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2)
{
double cateto_opuesto,cateto_adyacente, hipotenusa, distancia, marcacion;
double cateto_opuesto,cateto_adyacente, hipotenusa, distancia;
double marcacion = 0.0;
//latitude and longitude first point
@ -234,7 +235,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl @@ -234,7 +235,7 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
cateto_adyacente = abs((lon1-lon2));
hipotenusa = sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
distancia = hipotenusa*60;
distancia = hipotenusa*60.0;
if ((lat1 < lat2) && (lon1 > lon2)) //primer cuadrante

4
src/ui/map3D/Imagery.cc

@ -75,7 +75,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight, @@ -75,7 +75,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
return;
}
double tileResolution;
double tileResolution = 1.0;
if (currentImageryType == GOOGLE_SATELLITE ||
currentImageryType == GOOGLE_MAP)
{
@ -131,7 +131,7 @@ Imagery::draw2D(double windowWidth, double windowHeight, @@ -131,7 +131,7 @@ Imagery::draw2D(double windowWidth, double windowHeight,
return;
}
double tileResolution;
double tileResolution = 1.0;
if (currentImageryType == GOOGLE_SATELLITE ||
currentImageryType == GOOGLE_MAP)
{

2
src/ui/map3D/Pixhawk3DWidget.cc

@ -241,7 +241,7 @@ Pixhawk3DWidget::insertWaypoint(void) @@ -241,7 +241,7 @@ Pixhawk3DWidget::insertWaypoint(void)
{
if (uas)
{
Waypoint* wp;
Waypoint* wp = NULL;
if (frame == MAV_FRAME_GLOBAL)
{
double latitude = uas->getLatitude();

7
src/ui/map3D/PixhawkCheetahGeode.cc

@ -59300,9 +59300,10 @@ static GLfloat normals [22155][3] = { @@ -59300,9 +59300,10 @@ static GLfloat normals [22155][3] = {
GLfloat textures[1][2]={{0.0f,0.0f}};
/*Material indicies*/
/*{material index,face count}*/
static int material_ref [1][2] = {
{0,77848}
};
//static int material_ref [1][2] = {
//{0,77848}
//};
void MyMaterial(GLenum mode, GLfloat * f, GLfloat alpha)
{
GLfloat d[4];

4
src/ui/map3D/WaypointGroupNode.cc

@ -53,7 +53,9 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas) @@ -53,7 +53,9 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
{
if (uas)
{
double robotX, robotY, robotZ;
double robotX = 0.0;
double robotY = 0.0;
double robotZ = 0.0;
if (frame == MAV_FRAME_GLOBAL)
{
double latitude = uas->getLatitude();

1
src/ui/uas/UASView.cc

@ -215,6 +215,7 @@ void UASView::hideEvent(QHideEvent* event) @@ -215,6 +215,7 @@ void UASView::hideEvent(QHideEvent* event)
void UASView::receiveHeartbeat(UASInterface* uas)
{
Q_UNUSED(uas);
QString colorstyle;
heartbeatColor = QColor(20, 200, 20);
colorstyle = colorstyle.sprintf("QGroupBox { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}",

Loading…
Cancel
Save