Commit 7c6cb936 authored by tecnosapiens's avatar tecnosapiens

add new Widget for global waypoint whit functionalities for edition of waypoints created

parent e605f2dc
...@@ -97,6 +97,36 @@ namespace qmapcontrol ...@@ -97,6 +97,36 @@ namespace qmapcontrol
geometries.clear(); geometries.clear();
} }
Geometry* Layer::get_Geometry(int index)
{
if(geometrySelected)
{
return geometrySelected;
}
else
{
for(int i = 0; i <= geometries.size(); i++)
{
Geometry *geometry = geometries[i];
if(geometry->name() == QString::number(index))
{
return geometry;
}
}
// foreach(Geometry *geometry, geometries)
// {
// if(geometry->name() == QString::number(index))
// {
// return geometry;
// }
// }
}
}
bool Layer::isVisible() const bool Layer::isVisible() const
{ {
return visible; return visible;
...@@ -323,3 +353,5 @@ namespace qmapcontrol ...@@ -323,3 +353,5 @@ namespace qmapcontrol
mapAdapter = mapadapter; mapAdapter = mapadapter;
} }
} }
...@@ -200,6 +200,12 @@ namespace qmapcontrol ...@@ -200,6 +200,12 @@ namespace qmapcontrol
*/ */
void setVisible(bool visible); void setVisible(bool visible);
//! get geometry selected by index
/*!
* @param index of geometry selected
*/
Geometry* get_Geometry(int index);
}; };
} }
#endif #endif
...@@ -109,6 +109,8 @@ MainWindow::MainWindow(QWidget *parent) : ...@@ -109,6 +109,8 @@ MainWindow::MainWindow(QWidget *parent) :
// it notifies that a waypoint global goes to do create and a map graphic too // it notifies that a waypoint global goes to do create and a map graphic too
connect(waypoints, SIGNAL(createWaypointAtMap(QPointF)), map, SLOT(createWaypointGraphAtMap(QPointF))); connect(waypoints, SIGNAL(createWaypointAtMap(QPointF)), map, SLOT(createWaypointGraphAtMap(QPointF)));
// it notifies that a waypoint global change its position by spinBox on Widget WaypointView
connect(waypoints, SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), map, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
} }
MainWindow::~MainWindow() MainWindow::~MainWindow()
......
...@@ -49,6 +49,8 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -49,6 +49,8 @@ MapWidget::MapWidget(QWidget *parent) :
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
waypointIsDrag = false;
// Accept focus by clicking or keyboard // Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus); this->setFocusPolicy(Qt::StrongFocus);
...@@ -397,6 +399,8 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ ...@@ -397,6 +399,8 @@ 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);
waypointIsDrag = true;
// Refresh the screen // Refresh the screen
mc->updateRequestNew(); mc->updateRequestNew();
...@@ -418,6 +422,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ ...@@ -418,6 +422,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{ {
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning); mc->setMouseMode(qmapcontrol::MapControl::Panning);
...@@ -597,10 +602,35 @@ void MapWidget::clearPath() ...@@ -597,10 +602,35 @@ void MapWidget::clearPath()
wpIndex.clear(); wpIndex.clear();
mc->updateRequestNew(); mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket // si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicked
if(createPath->isChecked()) if(createPath->isChecked())
{ {
createPath->click(); createPath->click();
} }
} }
void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon)
{
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();
}
}
...@@ -65,6 +65,7 @@ public slots: ...@@ -65,6 +65,7 @@ public slots:
//ROCA //ROCA
void clearPath(); void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
protected: protected:
void changeEvent(QEvent* e); void changeEvent(QEvent* e);
...@@ -114,6 +115,7 @@ protected: ...@@ -114,6 +115,7 @@ protected:
signals: signals:
//void movePoint(QPointF newCoord); //void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA void captureMapCoordinateClick(const QPointF coordinate); //ROCA
...@@ -127,6 +129,7 @@ private: ...@@ -127,6 +129,7 @@ private:
QHash <QString, Point*> wpIndex; QHash <QString, Point*> wpIndex;
LineString* path; LineString* path;
QPen* pointPen; QPen* pointPen;
bool waypointIsDrag;
}; };
#endif // MAPWIDGET_H #endif // MAPWIDGET_H
...@@ -12,14 +12,29 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) : ...@@ -12,14 +12,29 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) :
ui->m_orbitalSpinBox->hide(); ui->m_orbitalSpinBox->hide();
// Read values and set user interface
updateValues();
connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double))); connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double))); connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
//for spinBox Latitude
connect(ui->m_latitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLatitudeWP(int)));
connect(ui->m_latitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLatitudeMinuteWP(double)));
//for spinBox Longitude
connect(ui->m_longitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLongitudeWP(int)));
connect(ui->m_longitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLongitudeMinuteWP(double)));
// latitude spinBox
connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int))); connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
// Read values and set user interface
updateValues();
// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double))); // connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
...@@ -48,9 +63,50 @@ WaypointGlobalView::~WaypointGlobalView() ...@@ -48,9 +63,50 @@ WaypointGlobalView::~WaypointGlobalView()
void WaypointGlobalView::updateValues() void WaypointGlobalView::updateValues()
{ {
ui->m_latitudtextEdit->setText(getLatitudString(wp->getY())); // ui->m_latitudtextEdit->setText(getLatitudString(wp->getY()));
ui->m_longitudtextEdit->setText(getLongitudString(wp->getX()));
ui->idWP_label->setText(QString("%1").arg(wp->getId()));\ // ui->m_longitudtextEdit->setText(getLongitudString(wp->getX()));
int gradoLat, gradoLon;
float minLat, minLon;
QString dirLat, dirLon;
getLatitudeGradoMin(wp->getY(), &gradoLat, &minLat, &dirLat);
getLongitudGradoMin(wp->getX(), &gradoLon, &minLon, &dirLon);
//latitude on spinBox
ui->m_latitudGrados_spinBox->setValue(gradoLat);
ui->m_latitudMinutos_spinBox->setValue(minLat);
if(dirLat == "N")
{
ui->m_dirLatitudeN_radioButton->setChecked(true);
ui->m_dirLatitudeS_radioButton->setChecked(false);
}
else
{
ui->m_dirLatitudeS_radioButton->setChecked(true);
ui->m_dirLatitudeN_radioButton->setChecked(false);
}
ui->m_longitudGrados_spinBox->setValue(gradoLon);
ui->m_longitudMinutos_spinBox->setValue(minLon);
if(dirLon == "W")
{
ui->m_dirLongitudeW_radioButton->setChecked(true);
ui->m_dirLongitudeE_radioButton->setChecked(false);
}
else
{
ui->m_dirLongitudeE_radioButton->setChecked(true);
ui->m_dirLongitudeW_radioButton->setChecked(false);
}
ui->idWP_label->setText(QString("WP-%1").arg(wp->getId()));
} }
...@@ -152,4 +208,205 @@ void WaypointGlobalView::changeOrbitalState(int state) ...@@ -152,4 +208,205 @@ void WaypointGlobalView::changeOrbitalState(int state)
} }
} }
void WaypointGlobalView::getLatitudeGradoMin(float latitud, int *gradoLat, float *minLat, QString *dirLat)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (latitud<0){*dirLat="S"; latitud = latitud * -1;}
else {*dirLat="N";}
if(latitud< 90 || latitud > -90)
{
dec = latitud - (entero = ::floor(latitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
*gradoLat = grados;
*minLat = minutos;
}
else
{
*gradoLat = -1;
*minLat = -1;
*dirLat="N/A";
}
}
void WaypointGlobalView::getLongitudGradoMin(float longitud, int *gradoLon, float *minLon, QString *dirLon)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (longitud<0){*dirLon="W"; longitud = longitud * -1;}
else {*dirLon="E";}
if(longitud<180 || longitud > -180)
{
dec = longitud - (entero = ::floor(longitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
*gradoLon = grados;
*minLon = minutos;
}
else
{
*gradoLon = -1;
*minLon = -1;
*dirLon="N/A";
}
}
void WaypointGlobalView::updateCoordValues(float lat, float lon)
{
}
void WaypointGlobalView::updateLatitudeWP(int value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
//dirLat = ui->m_dirLatitud_label->text();
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLatitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
//dirLat = ui->m_dirLatitud_label->text();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeWP(int value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
...@@ -22,12 +22,28 @@ public slots: ...@@ -22,12 +22,28 @@ public slots:
void remove(); void remove();
QString getLatitudString(float lat); QString getLatitudString(float lat);
QString getLongitudString(float lon); QString getLongitudString(float lon);
void getLatitudeGradoMin(float lat, int *gradoLat, float *minLat, QString *dirLat);
void getLongitudGradoMin(float lon, int *gradoLon, float *minLon, QString *dirLon);
void changeOrbitalState(int state); void changeOrbitalState(int state);
void updateCoordValues(float lat, float lon);
//update latitude
void updateLatitudeWP(int value);
void updateLatitudeMinuteWP(double value);
//update longitude
void updateLongitudeWP(int value);
void updateLongitudeMinuteWP(double value);
signals: signals:
void removeWaypoint(Waypoint*); void removeWaypoint(Waypoint*);
void changePositionWP(Waypoint*);
protected: protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
......
This diff is collapsed.
...@@ -325,9 +325,11 @@ void WaypointList::waypointListChanged() ...@@ -325,9 +325,11 @@ void WaypointList::waypointListChanged()
{ {
WaypointGlobalView* wpview = new WaypointGlobalView(wp, this); WaypointGlobalView* wpview = new WaypointGlobalView(wp, this);
wpGlobalViews.insert(wp, wpview); wpGlobalViews.insert(wp, wpview);
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
connect(wpview, SIGNAL(changePositionWP(Waypoint*)), this, SLOT(changeWPPositionBySpinBox(Waypoint*)));
// connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); // connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
// connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); // connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); // connect(wpview, SIGNAL(changePositionWP(Waypoint*)), this, SLOT(waypointGlobalPositionChanged(Waypoint*)));
// connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); // connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
// connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16))); // connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
} }
...@@ -547,10 +549,13 @@ void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate) ...@@ -547,10 +549,13 @@ void WaypointList::setIsWPGlobal(bool value, QPointF centerCoordinate)
if(ret) if(ret)
{ {
clearLocalWPWidget(); clearLocalWPWidget();
isGlobalWP = value;
isLocalWP = !(value);
} }
} }
isLocalWP = !value;
isGlobalWP = value;
} }
...@@ -583,6 +588,19 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP) ...@@ -583,6 +588,19 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
} }
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
//}
void WaypointList::clearLocalWPWidget() void WaypointList::clearLocalWPWidget()
{ {
if (uas) if (uas)
...@@ -598,3 +616,9 @@ void WaypointList::clearLocalWPWidget() ...@@ -598,3 +616,9 @@ void WaypointList::clearLocalWPWidget()
} }
} }
} }
void WaypointList::changeWPPositionBySpinBox(Waypoint *wp)
{
emit changePositionWPGlobalBySpinBox(wp->getId(), wp->getY(), wp->getX());
}
...@@ -95,6 +95,8 @@ public slots: ...@@ -95,6 +95,8 @@ public slots:
void clearLocalWPWidget(); void clearLocalWPWidget();
void changeWPPositionBySpinBox(Waypoint* wp);
// Waypoint operations // Waypoint operations
void moveUp(Waypoint* wp); void moveUp(Waypoint* wp);
void moveDown(Waypoint* wp); void moveDown(Waypoint* wp);
...@@ -106,6 +108,8 @@ public slots: ...@@ -106,6 +108,8 @@ public slots:
signals: signals:
void clearPathclicked(); void clearPathclicked();
void createWaypointAtMap(const QPointF coordinate); void createWaypointAtMap(const QPointF coordinate);
// void ChangeWaypointGlobalPosition(int index, QPointF coord);
void changePositionWPGlobalBySpinBox(int indexWP, float lat, float lon);
......
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