1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-29 07:24:13 +01:00

New map temporary user control panel updates

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@825 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
pip 2010-06-20 08:51:18 +00:00 committed by pip
parent 3ea868a253
commit 22ccee665b
3 changed files with 543 additions and 440 deletions

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>349</width>
<height>378</height>
<width>404</width>
<height>449</height>
</rect>
</property>
<property name="sizePolicy">
@ -48,8 +48,8 @@
<rect>
<x>0</x>
<y>10</y>
<width>341</width>
<height>366</height>
<width>386</width>
<height>381</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
@ -92,7 +92,7 @@
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:pad, x1:0, y1:0, x2:0, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(80, 80, 80, 255));
color: rgb(255, 255, 255);</string>
color: rgb(85, 255, 127);</string>
</property>
<property name="text">
<string>labelStatus</string>
@ -104,6 +104,22 @@ color: rgb(255, 255, 255);</string>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="leftMargin">
@ -149,7 +165,8 @@ color: rgb(255, 255, 255, 200);</string>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 255, 255, 64);</string>
<string notr="true">background-color: rgba(255, 255, 255, 64);
color: rgb(255, 255, 255);</string>
</property>
</widget>
</item>
@ -707,7 +724,7 @@ color: rgb(255, 255, 255);</string>
color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>ShowGridLines</string>
<string>Grid Lines</string>
</property>
<property name="checked">
<bool>false</bool>
@ -731,215 +748,246 @@ color: rgb(255, 255, 255);</string>
color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>UseOpenGL</string>
<string>OpenGL</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="font">
<font>
<pointsize>7</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 255, 255, 0);
color: rgb(255, 255, 127);</string>
<string notr="true">background-color: qlineargradient(spread:pad, x1:0, y1:0, x2:0, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(80, 80, 80, 255));
color: rgb(85, 255, 127);</string>
</property>
<property name="title">
<property name="text">
<string>Way Points</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="flat">
<bool>true</bool>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="leftMargin">
<number>5</number>
</property>
<layout class="QVBoxLayout" name="verticalLayout_9">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>5</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>5</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="leftMargin">
<number>5</number>
</property>
<property name="rightMargin">
<number>5</number>
</property>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="pushButtonDeleteWayPoint">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="cursor">
<cursorShape>OpenHandCursor</cursorShape>
</property>
<property name="toolTip">
<string>Delete a Way Point</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/minus.png</normaloff>:/core/images/minus.png</iconset>
</property>
<property name="iconSize">
<size>
<width>12</width>
<height>12</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="pushButtonAddWayPoint">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="cursor">
<cursorShape>OpenHandCursor</cursorShape>
</property>
<property name="toolTip">
<string>Add a new Way Point</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/plus.png</normaloff>:/core/images/plus.png</iconset>
</property>
<property name="iconSize">
<size>
<width>12</width>
<height>12</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QTableWidget" name="tableWidgetWayPoints">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 255, 255, 0);
<property name="rightMargin">
<number>5</number>
</property>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="pushButtonDeleteWayPoint">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="cursor">
<cursorShape>OpenHandCursor</cursorShape>
</property>
<property name="toolTip">
<string>Delete a Way Point</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/minus.png</normaloff>:/core/images/minus.png</iconset>
</property>
<property name="iconSize">
<size>
<width>12</width>
<height>12</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="pushButtonAddWayPoint">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="cursor">
<cursorShape>OpenHandCursor</cursorShape>
</property>
<property name="toolTip">
<string>Add a new Way Point</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/plus.png</normaloff>:/core/images/plus.png</iconset>
</property>
<property name="iconSize">
<size>
<width>12</width>
<height>12</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QTableWidget" name="tableWidgetWayPoints">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 255, 255, 0);
color: rgb(0, 0, 0);
</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="showGrid">
<bool>false</bool>
</property>
<property name="gridStyle">
<enum>Qt::DotLine</enum>
</property>
<property name="wordWrap">
<bool>false</bool>
</property>
<property name="rowCount">
<number>0</number>
</property>
<attribute name="horizontalHeaderStretchLastSection">
<bool>true</bool>
</attribute>
<attribute name="verticalHeaderCascadingSectionResizes">
<bool>false</bool>
</attribute>
<attribute name="verticalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>true</bool>
</attribute>
<attribute name="verticalHeaderCascadingSectionResizes">
<bool>false</bool>
</attribute>
<attribute name="verticalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<column>
<property name="text">
<string>Num</string>
</property>
<property name="textAlignment">
<set>AlignLeft|AlignVCenter</set>
</property>
</column>
<column>
<property name="text">
<string>Latitude</string>
</property>
</column>
<column>
<property name="text">
<string>Longitude</string>
</property>
</column>
</widget>
</item>
</layout>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="showGrid">
<bool>false</bool>
</property>
<property name="gridStyle">
<enum>Qt::DotLine</enum>
</property>
<property name="wordWrap">
<bool>false</bool>
</property>
<property name="cornerButtonEnabled">
<bool>false</bool>
</property>
<property name="rowCount">
<number>0</number>
</property>
<property name="columnCount">
<number>4</number>
</property>
<attribute name="horizontalHeaderVisible">
<bool>true</bool>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>true</bool>
</attribute>
<attribute name="verticalHeaderCascadingSectionResizes">
<bool>false</bool>
</attribute>
<attribute name="verticalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>true</bool>
</attribute>
<attribute name="horizontalHeaderVisible">
<bool>true</bool>
</attribute>
<attribute name="verticalHeaderCascadingSectionResizes">
<bool>false</bool>
</attribute>
<attribute name="verticalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<column>
<property name="text">
<string>Num</string>
</property>
<property name="textAlignment">
<set>AlignLeft|AlignVCenter</set>
</property>
</column>
<column>
<property name="text">
<string>Latitude</string>
</property>
</column>
<column>
<property name="text">
<string>Longitude</string>
</property>
</column>
<column>
<property name="text">
<string>Height</string>
</property>
</column>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>15</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_18">
<property name="leftMargin">
@ -954,33 +1002,6 @@ color: rgb(0, 0, 0);
<property name="bottomMargin">
<number>1</number>
</property>
<item>
<widget class="QLabel" name="label_14">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 255, 255, 0);
color: rgb(255, 255, 255, 200);</string>
</property>
<property name="text">
<string>Map Progress </string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="labelNumTilesToLoad">
<property name="sizePolicy">
@ -1011,7 +1032,7 @@ color: rgb(255, 255, 255);</string>
<item>
<widget class="QProgressBar" name="progressBarMap">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -1019,7 +1040,7 @@ color: rgb(255, 255, 255);</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
<height>0</height>
</size>
</property>
<property name="maximumSize">
@ -1032,19 +1053,54 @@ color: rgb(255, 255, 255);</string>
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgb(83, 83, 83);</string>
<string notr="true">QProgressBar {
/*border: 1px solid black;*/
border: none;
padding: 1px;
/*border-top-left-radius: 7px;
border-bottom-left-radius: 7px;*/
background-color: qlineargradient(spread:pad, x1:0, y1:0, x2:1, y2:0, stop:0 rgba(0, 0, 0, 255), stop:1 rgba(100, 100, 100, 255));
/*width: 15px;*/
color: rgb(255, 255, 255);
}
QProgressBar::chunk {
background-color: rgb(85, 85, 255);
border: none;
}</string>
</property>
<property name="value">
<number>0</number>
<number>50</number>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="textVisible">
<bool>false</bool>
<bool>true</bool>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="format">
<string>%v</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="pushButtonReload">
<property name="sizePolicy">

View File

@ -93,29 +93,30 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent)
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
// controlpanel_ui->labelNumTilesToLoad->setText(" 0");
controlpanel_ui->labelNumTilesToLoad->setText("");
controlpanel_ui->labelStatus->setText("");
controlpanel_ui->progressBarMap->setMaximum(1);
// **************
// for fetching a contiuous mouse position
map->SetFollowMouse(true);
// receive map zoom changes
connect(map, SIGNAL(zoomChanged(double)), this, SLOT(zoomChanged(double)));
// receive tile loading messages
connect(map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int)));
map->SetShowTileGridLines(controlpanel_ui->checkBox->isChecked());
// get current position data
// get current UAV data
PositionActual::DataFields data = m_positionActual->getData();
// set the default map position
map->SetCurrentPosition(internals::PointLatLng(data.Latitude, data.Longitude));
connect(map, SIGNAL(zoomChanged(double)), this, SLOT(zoomChanged(double))); // map zoom change signals
connect(map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals
connect(map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals
connect(map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals
connect(map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals
connect(map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed
connect(map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed
connect(map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error
connect(map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals
map->SetMaxZoom(20); // increase the maximum zoom level
map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions
map->SetFollowMouse(true); // we want a contiuous mouse position reading
map->SetUseOpenGL(controlpanel_ui->checkBox_2->isChecked()); // enable/disable openGL
map->SetShowTileGridLines(controlpanel_ui->checkBox->isChecked()); // map grid lines on/off
map->SetCurrentPosition(internals::PointLatLng(data.Latitude, data.Longitude)); // set the default map position
// **************
@ -135,6 +136,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent)
createMapOverlayUserControls();
// **************
// create the desired timers
m_updateTimer = new QTimer();
m_updateTimer->setInterval(250);
@ -142,7 +144,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent)
m_updateTimer->start();
m_statusUpdateTimer = new QTimer();
m_statusUpdateTimer->setInterval(40);
m_statusUpdateTimer->setInterval(100);
connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(statusUpdate()));
m_statusUpdateTimer->start();
@ -159,6 +161,7 @@ OPMapGadgetWidget::~OPMapGadgetWidget()
}
// *************************************************************************************
// widget signals
void OPMapGadgetWidget::resizeEvent(QResizeEvent *event)
{
@ -171,11 +174,16 @@ void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event)
{
if (map)
{
// fetch the current latitude and longitude for the current mouse position
// mouse_lat_lon = map->currentMousePosition();
// QString coord_str = "lat " + QString::number(lat_lon.Lat(), 'f', 6) + ", lon " + QString::number(lat_lon.Lng(), 'f', 6);
// controlpanel_ui->labelStatus->setText(coord_str);
// mouse_lat_lon = map->currentMousePosition(); // fetch the current mouse lat/longitude position
// if (mouse_lat_lon != lat_lon)
// { // the mouse has moved
// mouse_lat_lon = lat_lon;
//
// QString coord_str = " " + QString::number(mouse_lat_lon.Lat(), 'f', 6) + " " + QString::number(mouse_lat_lon.Lng(), 'f', 6);
//
// statusLabel.setText(coord_str);
// controlpanel_ui->labelStatus->setText(coord_str);
// }
}
if (event->buttons() & Qt::LeftButton)
@ -184,7 +192,225 @@ void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event)
}
}
void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event)
{
if (event->key() == Qt::Key_Escape) // ESC
{
}
else
if (event->key() == Qt::Key_F1) // F1
{
}
else
if (event->key() == Qt::Key_F2) // F2
{
}
else
if (event->key() == Qt::Key_Up)
{
}
else
if (event->key() == Qt::Key_Down)
{
}
else
if (event->key() == Qt::Key_Left)
{
}
else
if (event->key() == Qt::Key_Right)
{
}
else
if (event->key() == Qt::Key_PageUp)
{
}
else
if (event->key() == Qt::Key_PageDown)
{
}
else
{
qDebug() << event->key() << endl;
}
}
// *************************************************************************************
// timer signals
void OPMapGadgetWidget::updatePosition()
{
PositionActual::DataFields data = m_positionActual->getData(); // get current UAV data
if (map && m_follow_uav)
{
internals::PointLatLng uav_pos = internals::PointLatLng(data.Latitude, data.Longitude); // current UAV position
internals::PointLatLng map_pos = map->CurrentPosition(); // current MAP position
if (map_pos != uav_pos) map->SetCurrentPosition(uav_pos); // center the map onto the UAV
}
}
void OPMapGadgetWidget::statusUpdate()
{
internals::PointLatLng lat_lon = map->currentMousePosition(); // fetch the current lat/lon mouse position
if (mouse_lat_lon != lat_lon)
{ // the mouse has moved
mouse_lat_lon = lat_lon;
QString coord_str = " " + QString::number(mouse_lat_lon.Lat(), 'f', 6) + " " + QString::number(mouse_lat_lon.Lng(), 'f', 6);
statusLabel.setText(coord_str);
controlpanel_ui->labelStatus->setText(coord_str);
}
}
// *************************************************************************************
// map signals
void OPMapGadgetWidget::zoomChanged(double zoom)
{
controlpanel_ui->labelZoom->setText(" " + QString::number(zoom));
}
void OPMapGadgetWidget::OnMapDrag()
{
}
void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point)
{
}
void OPMapGadgetWidget::OnTilesStillToLoad(int number)
{
if (controlpanel_ui->progressBarMap->maximum() < number)
controlpanel_ui->progressBarMap->setMaximum(number); // update the maximum number of tiles used
controlpanel_ui->progressBarMap->setValue(controlpanel_ui->progressBarMap->maximum() - number); // update the progress bar
// controlpanel_ui->labelNumTilesToLoad->setText(" " + QString::number(number));
}
void OPMapGadgetWidget::OnTileLoadStart()
{
controlpanel_ui->progressBarMap->setVisible(true);
}
void OPMapGadgetWidget::OnTileLoadComplete()
{
controlpanel_ui->progressBarMap->setVisible(false);
}
void OPMapGadgetWidget::OnMapZoomChanged()
{
}
void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type)
{
}
void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos)
{
}
// *************************************************************************************
// user control panel signals
void OPMapGadgetWidget::on_checkBox_clicked(bool checked)
{
if (map)
map->SetShowTileGridLines(checked);
}
void OPMapGadgetWidget::on_checkBox_2_clicked(bool checked)
{
if (map)
map->SetUseOpenGL(checked);
}
void OPMapGadgetWidget::on_pushButtonGO_clicked()
{
if (map)
{
core::GeoCoderStatusCode::Types x = map->SetCurrentPositionByKeywords(controlpanel_ui->lineEdit->text());
controlpanel_ui->label->setText(mapcontrol::Helper::StrFromGeoCoderStatusCode(x));
}
}
void OPMapGadgetWidget::on_pushButtonReload_clicked()
{
if (map)
map->ReloadMap();
}
void OPMapGadgetWidget::on_pushButtonRL_clicked()
{
if (map)
{
map->SetRotate(map->Rotate() - 1);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonRC_clicked()
{
if (map)
{
map->SetRotate(0);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonRR_clicked()
{
if (map)
{
map->SetRotate(map->Rotate() + 1);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonZoomP_clicked()
{
zoomIn();
}
void OPMapGadgetWidget::on_pushButtonZoomM_clicked()
{
zoomOut();
}
void OPMapGadgetWidget::on_pushButtonGeoFenceM_clicked()
{
int geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
int step = controlpanel_ui->spinBoxGeoFenceDistance->singleStep();
controlpanel_ui->spinBoxGeoFenceDistance->setValue(geo_fence_distance - step);
geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
// to do
}
void OPMapGadgetWidget::on_pushButtonGeoFenceP_clicked()
{
int geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
int step = controlpanel_ui->spinBoxGeoFenceDistance->singleStep();
controlpanel_ui->spinBoxGeoFenceDistance->setValue(geo_fence_distance + step);
geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
// to do
}
// *************************************************************************************
// public functions
void OPMapGadgetWidget::zoomIn()
{
@ -248,193 +474,6 @@ void OPMapGadgetWidget::setCacheLocation(QString cacheLocation)
map->configuration->SetCacheLocation(cacheLocation);
}
// *************************************************************************************
void OPMapGadgetWidget::updatePosition()
{
// get current position data
PositionActual::DataFields data = m_positionActual->getData();
if (map && m_follow_uav)
{ // center the map onto the UAV
map->SetCurrentPosition(internals::PointLatLng(data.Latitude, data.Longitude));
}
}
void OPMapGadgetWidget::statusUpdate()
{
// fetch the current latitude and longitude for the current mouse position
internals::PointLatLng lat_lon = map->currentMousePosition();
if (mouse_lat_lon != lat_lon)
{
mouse_lat_lon = lat_lon;
QString coord_str = " " + QString::number(mouse_lat_lon.Lat(), 'f', 6) + " " + QString::number(mouse_lat_lon.Lng(), 'f', 6);
statusLabel.setText(coord_str);
controlpanel_ui->labelStatus->setText(coord_str);
}
}
// *************************************************************************************
void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event)
{
if (event->key() == Qt::Key_Escape) // ESC
{
}
else
if (event->key() == Qt::Key_F1) // F1
{
}
else
if (event->key() == Qt::Key_F2) // F2
{
}
else
if (event->key() == Qt::Key_Up)
{
}
else
if (event->key() == Qt::Key_Down)
{
}
else
if (event->key() == Qt::Key_Left)
{
}
else
if (event->key() == Qt::Key_Right)
{
}
else
if (event->key() == Qt::Key_PageUp)
{
}
else
if (event->key() == Qt::Key_PageDown)
{
}
else
{
qDebug() << event->key() << endl;
}
}
// *************************************************************************************
// signals from the map library
void OPMapGadgetWidget::zoomChanged(double zoom)
{
controlpanel_ui->labelZoom->setText(" " + QString::number(zoom));
}
void OPMapGadgetWidget::OnTilesStillToLoad(int number)
{
if (controlpanel_ui->progressBarMap->maximum() < number)
controlpanel_ui->progressBarMap->setMaximum(number);
controlpanel_ui->progressBarMap->setValue(controlpanel_ui->progressBarMap->maximum() - number);
// controlpanel_ui->labelNumTilesToLoad->setText(" " + QString::number(number));
}
// *************************************************************************************
void OPMapGadgetWidget::on_checkBox_clicked(bool checked)
{
if (map)
map->SetShowTileGridLines(checked);
}
void OPMapGadgetWidget::on_pushButtonGO_clicked()
{
if (map)
{
core::GeoCoderStatusCode::Types x = map->SetCurrentPositionByKeywords(controlpanel_ui->lineEdit->text());
controlpanel_ui->label->setText(mapcontrol::Helper::StrFromGeoCoderStatusCode(x));
}
}
void OPMapGadgetWidget::on_pushButtonReload_clicked()
{
if (map)
map->ReloadMap();
}
void OPMapGadgetWidget::on_pushButtonRL_clicked()
{
if (map)
{
map->SetRotate(map->Rotate() - 1);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonRC_clicked()
{
if (map)
{
map->SetRotate(0);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonRR_clicked()
{
if (map)
{
map->SetRotate(map->Rotate() + 1);
controlpanel_ui->labelRotate->setText(" " + QString::number(map->Rotate()));
}
}
void OPMapGadgetWidget::on_pushButtonZoomP_clicked()
{
zoomIn();
}
void OPMapGadgetWidget::on_pushButtonZoomM_clicked()
{
zoomOut();
}
void OPMapGadgetWidget::on_checkBox_2_clicked(bool checked)
{
if (map)
map->SetUseOpenGL(checked);
}
void OPMapGadgetWidget::on_pushButtonGeoFenceM_clicked()
{
int geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
int step = controlpanel_ui->spinBoxGeoFenceDistance->singleStep();
controlpanel_ui->spinBoxGeoFenceDistance->setValue(geo_fence_distance - step);
geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
// to do
}
void OPMapGadgetWidget::on_pushButtonGeoFenceP_clicked()
{
int geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
int step = controlpanel_ui->spinBoxGeoFenceDistance->singleStep();
controlpanel_ui->spinBoxGeoFenceDistance->setValue(geo_fence_distance + step);
geo_fence_distance = controlpanel_ui->spinBoxGeoFenceDistance->value();
// to do
}
// *************************************************************************************
// create some user controls overlayed onto the map area
@ -466,7 +505,7 @@ void OPMapGadgetWidget::createMapOverlayUserControls()
zoomout->setFlat(true);
zoomout->setIcon(QIcon(QString::fromUtf8(":/opmap/images/minus.png")));
zoomout->setIconSize(QSize(32, 32));
zoomout->setFixedSize(32, 32);
zoomout->setFixedSize(28, 28);
connect(zoomout, SIGNAL(clicked(bool)), this, SLOT(zoomOut()));
// QPushButton *zoomin = createTransparentButton(map, "", QString::fromUtf8(":/core/images/plus.png"));
@ -477,7 +516,7 @@ void OPMapGadgetWidget::createMapOverlayUserControls()
zoomin->setCursor(Qt::OpenHandCursor);
zoomin->setIcon(QIcon(QString::fromUtf8(":/opmap/images/plus.png")));
// zoomin->setIconSize(QSize(12, 12));
zoomin->setIconSize(QSize(32, 32));
zoomin->setIconSize(QSize(28, 28));
zoomin->setFixedSize(32, 32);
// zoomin->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Minimum);
connect(zoomin, SIGNAL(clicked(bool)), this, SLOT(zoomIn()));

View File

@ -79,7 +79,15 @@ private slots:
void on_pushButtonGeoFenceP_clicked();
void on_checkBox_2_clicked(bool checked);
// map signals
void zoomChanged(double zoom);
void OnCurrentPositionChanged(internals::PointLatLng point);
void OnTileLoadComplete();
void OnTileLoadStart();
void OnMapDrag();
void OnMapZoomChanged();
void OnMapTypeChanged(MapType::Types type);
void OnEmptyTileError(int zoom, core::Point pos);
void OnTilesStillToLoad(int number);
private: