Browse Source

added functions to create global waypoinst, modifying the WaypointList class, MapWidget and MainWindows.

QGC4.4
tecnosapiens 15 years ago
parent
commit
4c2798a8ba
  1. 8
      lib/QMapControl/src/geometry.cpp
  2. 10
      lib/QMapControl/src/geometry.h
  3. 2
      src/ui/MainWindow.cc
  4. 32
      src/ui/MapWidget.cc
  5. 1
      src/ui/MapWidget.h
  6. 133
      src/ui/WaypointList.cc
  7. 8
      src/ui/WaypointList.h

8
lib/QMapControl/src/geometry.cpp

@ -29,9 +29,9 @@ namespace qmapcontrol
Geometry::Geometry(QString name) Geometry::Geometry(QString name)
: GeometryType("Geometry"), myparentGeometry(0), mypen(0), visible(true), myname(name) : GeometryType("Geometry"), myparentGeometry(0), mypen(0), visible(true), myname(name)
{ {
myIndex = name.toInt(0,10);
} }
Geometry::~Geometry() Geometry::~Geometry()
{ {
} }
@ -40,6 +40,11 @@ namespace qmapcontrol
{ {
return myname; return myname;
} }
int Geometry::get_myIndex() const
{
return myIndex;
}
Geometry* Geometry::parentGeometry() const Geometry* Geometry::parentGeometry() const
{ {
return myparentGeometry; return myparentGeometry;
@ -85,4 +90,5 @@ namespace qmapcontrol
{ {
return mypen; return mypen;
} }
} }

10
lib/QMapControl/src/geometry.h

@ -49,6 +49,7 @@ namespace qmapcontrol
Q_OBJECT Q_OBJECT
public: public:
explicit Geometry(QString name = QString()); explicit Geometry(QString name = QString());
virtual ~Geometry(); virtual ~Geometry();
QString GeometryType; QString GeometryType;
@ -74,6 +75,12 @@ namespace qmapcontrol
*/ */
QString name() const; QString name() const;
//! returns the index of this Geometry
/*!
* @return the index of this Geometry
*/
int get_myIndex() const;
//! returns the parent Geometry of this Geometry //! returns the parent Geometry of this Geometry
/*! /*!
* A LineString is a composition of many Points. This methods returns the parent (the LineString) of a Point * A LineString is a composition of many Points. This methods returns the parent (the LineString) of a Point
@ -123,6 +130,7 @@ namespace qmapcontrol
QPen* mypen; QPen* mypen;
bool visible; bool visible;
QString myname; QString myname;
int myIndex;
void setParentGeometry(Geometry* geom); void setParentGeometry(Geometry* geom);
signals: signals:
@ -149,6 +157,8 @@ namespace qmapcontrol
* @param visible if the layer should be visible * @param visible if the layer should be visible
*/ */
virtual void setVisible(bool visible); virtual void setVisible(bool visible);
}; };
} }
#endif #endif

2
src/ui/MainWindow.cc

@ -104,6 +104,8 @@ MainWindow::MainWindow(QWidget *parent) :
connect(map, SIGNAL(captureMapCoordinateClick(QPointF)), waypoints, SLOT(addWaypointMouse(QPointF))); connect(map, SIGNAL(captureMapCoordinateClick(QPointF)), waypoints, SLOT(addWaypointMouse(QPointF)));
// it notifies that a waypoint global goes to do create // it notifies that a waypoint global goes to do create
connect(map, SIGNAL(createGlobalWP(bool)), waypoints, SLOT(setIsWPGlobal(bool))); connect(map, SIGNAL(createGlobalWP(bool)), waypoints, SLOT(setIsWPGlobal(bool)));
connect(map, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypoints, SLOT(waypointGlobalChanged(QPointF,int)) );
} }
MainWindow::~MainWindow() MainWindow::~MainWindow()

32
src/ui/MapWidget.cc

@ -87,7 +87,10 @@ MapWidget::MapWidget(QWidget *parent) :
// Set default zoom level // Set default zoom level
mc->setZoom(16); mc->setZoom(16);
// Zurich, ETH // Zurich, ETH
mc->setView(QPointF(8.548056,47.376389)); //mc->setView(QPointF(8.548056,47.376389));
// Veracruz Mexico, ETH
mc->setView(QPointF(-96.105208,19.138955));
// Add controls to select map provider // Add controls to select map provider
///////////////////////////////////////////////// /////////////////////////////////////////////////
@ -336,7 +339,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
// Create waypoint name // Create waypoint name
QString str; QString str;
str = QString("WP%1").arg(path->numberOfPoints()); str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path // create the WP and set everything in the LineString to display the path
CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str); CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
@ -369,6 +372,10 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
Q_UNUSED(coordinate); Q_UNUSED(coordinate);
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
Point* point2Find; Point* point2Find;
point2Find = wpIndex[geom->name()]; point2Find = wpIndex[geom->name()];
point2Find->setCoordinate(coordinate); point2Find->setCoordinate(coordinate);
@ -376,12 +383,18 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
point2Find = dynamic_cast <Point*> (geom); point2Find = dynamic_cast <Point*> (geom);
point2Find->setCoordinate(coordinate); point2Find->setCoordinate(coordinate);
// Refresh the screen // qDebug() << geom->name();
mc->updateRequestNew(); temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
} }
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate){ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
mc->setMouseMode(qmapcontrol::MapControl::Panning); {
mc->setMouseMode(qmapcontrol::MapControl::Panning);
// qDebug() << geom->name(); // qDebug() << geom->name();
// qDebug() << geom->GeometryType; // qDebug() << geom->GeometryType;
@ -558,4 +571,11 @@ void MapWidget::clearPath()
mc->layer("Waypoints")->addGeometry(path); mc->layer("Waypoints")->addGeometry(path);
wpIndex.clear(); wpIndex.clear();
mc->updateRequestNew(); mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket
if(createPath->isChecked())
{
createPath->click();
}
} }

1
src/ui/MapWidget.h

@ -117,6 +117,7 @@ protected:
//void movePoint(QPointF newCoord); //void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value); void createGlobalWP(bool value);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
private: private:

133
src/ui/WaypointList.cc

@ -38,6 +38,7 @@ This file is part of the PIXHAWK project
#include <QDebug> #include <QDebug>
#include <QFileDialog> #include <QFileDialog>
#include "WaypointGlobalView.h" #include "WaypointGlobalView.h"
#include <QMessageBox>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) : WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent), QWidget(parent),
@ -88,6 +89,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
this->setVisible(false); this->setVisible(false);
isGlobalWP = false; isGlobalWP = false;
isLocalWP = false;
} }
WaypointList::~WaypointList() WaypointList::~WaypointList()
@ -166,18 +168,24 @@ void WaypointList::add()
{ {
if (uas) if (uas)
{ {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0) const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
{ if (waypoints.size() > 0)
Waypoint *last = waypoints.at(waypoints.size()-1); {
Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime()); Waypoint *last = waypoints.at(waypoints.size()-1);
uas->getWaypointManager().localAddWaypoint(wp); Waypoint *wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getYaw(), last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
} uas->getWaypointManager().localAddWaypoint(wp);
else }
{ else
Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000); {
uas->getWaypointManager().localAddWaypoint(wp); Waypoint *wp = new Waypoint(0, 1.1, 1.1, -0.8, 0.0, true, true, 0.15, 2000);
} uas->getWaypointManager().localAddWaypoint(wp);
}
isLocalWP = true;
} }
} }
@ -185,17 +193,27 @@ void WaypointList::addCurrentPositonWaypoint()
{ {
if (uas) if (uas)
{ {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); // For Global Waypoints
if (waypoints.size() > 0) if(isGlobalWP)
{ {
Waypoint *last = waypoints.at(waypoints.size()-1); isLocalWP = false;
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
} }
else else
{ {
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
uas->getWaypointManager().localAddWaypoint(wp); if (waypoints.size() > 0)
{
Waypoint *last = waypoints.at(waypoints.size()-1);
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., last->getAutoContinue(), false, last->getOrbit(), last->getHoldTime());
uas->getWaypointManager().localAddWaypoint(wp);
}
else
{
Waypoint *wp = new Waypoint(0, (qRound(mavX*100))/100., (qRound(mavY*100))/100., (qRound(mavZ*100))/100., (qRound(mavYaw*100))/100., true, true, 0.15, 2000);
uas->getWaypointManager().localAddWaypoint(wp);
}
isLocalWP = true;
} }
} }
} }
@ -244,10 +262,10 @@ void WaypointList::waypointListChanged()
{ {
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
// For Global Waypoints // For Global Waypoints
if(isGlobalWP) if(isGlobalWP)
{ {
isLocalWP = false;
// first remove all views of non existing waypoints // first remove all views of non existing waypoints
if (!wpGlobalViews.empty()) if (!wpGlobalViews.empty())
{ {
@ -420,22 +438,24 @@ void WaypointList::changeEvent(QEvent *e)
void WaypointList::on_clearWPListButton_clicked() void WaypointList::on_clearWPListButton_clicked()
{ {
emit clearPathclicked();
if (uas) if (uas)
{ {
if(isGlobalWP) if(isGlobalWP)
{ {
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++) while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{ {
//Waypoint *temp = waypoints[i];
WaypointGlobalView* widget = wpGlobalViews.find(waypoints[0]).value(); WaypointGlobalView* widget = wpGlobalViews.find(waypoints[0]).value();
widget->remove(); widget->remove();
} }
isGlobalWP = false; isGlobalWP = false;
@ -448,13 +468,14 @@ void WaypointList::on_clearWPListButton_clicked()
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList(); const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++) while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{ {
//Waypoint *temp = waypoints[i];
WaypointView* widget = wpViews.find(waypoints[0]).value(); WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove(); widget->remove();
} }
} }
} }
@ -484,5 +505,69 @@ void WaypointList::addWaypointMouse(QPointF coordinate)
/** @brief it notifies that a global waypoint goes to do created */ /** @brief it notifies that a global waypoint goes to do created */
void WaypointList::setIsWPGlobal(bool value) void WaypointList::setIsWPGlobal(bool value)
{ {
isGlobalWP = value;
if(isLocalWP)
{
if(wpViews.size()!= 0)
{
int ret = QMessageBox::warning(this, tr("My Application"),
tr("There are Waypoints local created.\n"
"Do you want to clear them?"),
QMessageBox::Ok | QMessageBox::Cancel);
if(ret)
{
clearLocalWPWidget();
isGlobalWP = value;
isLocalWP = !(value);
}
}
}
else
{
isGlobalWP = value;
}
}
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
if (waypoints.size() > 0)
{
Waypoint *temp = waypoints.at(indexWP);
temp->setX(coordinate.x());
temp->setY(coordinate.y());
WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
widget->updateValues();
}
}
}
void WaypointList::clearLocalWPWidget()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
} }

8
src/ui/WaypointList.h

@ -90,12 +90,19 @@ public slots:
/** @brief The waypoint manager informs that the waypoint list was changed */ /** @brief The waypoint manager informs that the waypoint list was changed */
void waypointListChanged(void); void waypointListChanged(void);
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void waypointGlobalChanged(const QPointF coordinate, const int indexWP);
void clearLocalWPWidget();
// Waypoint operations // Waypoint operations
void moveUp(Waypoint* wp); void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp); void moveDown(Waypoint* wp);
void removeWaypoint(Waypoint* wp); void removeWaypoint(Waypoint* wp);
signals: signals:
void clearPathclicked(); void clearPathclicked();
@ -114,6 +121,7 @@ protected:
double mavZ; double mavZ;
double mavYaw; double mavYaw;
bool isGlobalWP; bool isGlobalWP;
bool isLocalWP;
private: private:
Ui::WaypointList *m_ui; Ui::WaypointList *m_ui;

Loading…
Cancel
Save