Subversion Repositories Projects

Rev

Rev 674 | Rev 750 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 674 Rev 711
1
/***************************************************************************
1
/***************************************************************************
2
 *   Copyright (C) 2009 by Manuel Schrape                                  *
2
 *   Copyright (C) 2009 by Manuel Schrape                                  *
3
 *   manuel.schrape@gmx.de                                                 *
3
 *   manuel.schrape@gmx.de                                                 *
4
 *                                                                         *
4
 *                                                                         *
5
 *   This program is free software; you can redistribute it and/or modify  *
5
 *   This program is free software; you can redistribute it and/or modify  *
6
 *   it under the terms of the GNU General Public License as published by  *
6
 *   it under the terms of the GNU General Public License as published by  *
7
 *   the Free Software Foundation; either version 2 of the License.        *
7
 *   the Free Software Foundation; either version 2 of the License.        *
8
 *                                                                         *
8
 *                                                                         *
9
 *   This program is distributed in the hope that it will be useful,       *
9
 *   This program is distributed in the hope that it will be useful,       *
10
 *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
10
 *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
11
 *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
11
 *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
12
 *   GNU General Public License for more details.                          *
12
 *   GNU General Public License for more details.                          *
13
 *                                                                         *
13
 *                                                                         *
14
 *   You should have received a copy of the GNU General Public License     *
14
 *   You should have received a copy of the GNU General Public License     *
15
 *   along with this program; if not, write to the                         *
15
 *   along with this program; if not, write to the                         *
16
 *   Free Software Foundation, Inc.,                                       *
16
 *   Free Software Foundation, Inc.,                                       *
17
 *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
17
 *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
18
 ***************************************************************************/
18
 ***************************************************************************/
-
 
19
 
19
 
20
#include <QCryptographicHash>
20
#include <QMessageBox>
21
#include <QMessageBox>
21
#include <QDomDocument>
22
#include <QDomDocument>
22
#include <QFile>
23
#include <QFile>
23
 
24
 
24
#include "dlg_Main.h"
25
#include "dlg_Main.h"
25
#include "dlg_MapPos.h"
26
#include "dlg_MapPos.h"
26
 
27
 
27
// Konstruktor Main-Form
28
// Konstruktor Main-Form
28
dlg_Main::dlg_Main()
29
dlg_Main::dlg_Main()
29
{
30
{
30
    setupUi(this);
31
    setupUi(this);
31
 
32
 
32
    o_Settings = new cSettings();
33
    o_Settings = new cSettings();
33
 
34
 
34
    o_Input = new Input();
35
    o_Input = new Input();
35
 
36
 
36
    o_Map = new MapControl(QSize(25,25));
37
    o_Map = new MapControl(QSize(25,25));
37
    l_RouteWP = new LineString();
38
    l_RouteWP = new LineString();
38
    init_Directorys();
39
    init_Directorys();
39
    init_GUI();
40
    init_GUI();
40
    init_Connections();
41
    init_Connections();
41
}
42
}
42
 
43
 
43
// Grafische Oberfläche initialisieren
44
// Grafische Oberfläche initialisieren
44
void dlg_Main::init_GUI()
45
void dlg_Main::init_GUI()
45
{
46
{
46
    setWindowTitle(QA_NAME + " " + QA_VERSION);
47
    setWindowTitle(QA_NAME + " " + QA_VERSION);
47
 
48
 
48
    resize(o_Settings->GUI.Size);
49
    resize(o_Settings->GUI.Size);
49
    move(o_Settings->GUI.Point);
50
    move(o_Settings->GUI.Point);
50
 
51
 
51
    if (o_Settings->GUI.isMax)
52
    if (o_Settings->GUI.isMax)
52
    {
53
    {
53
        showMaximized();
54
        showMaximized();
54
    }
55
    }
55
 
56
 
56
    for(int z = 0; z < o_Settings->SERVER.IP_MAX; z++)
57
    for(int z = 0; z < o_Settings->SERVER.IP_MAX; z++)
57
    {
58
    {
58
        if (cb_Server->findText(o_Settings->SERVER.IP[z]) == -1)
59
        if (cb_Server->findText(o_Settings->SERVER.IP[z]) == -1)
59
        {
60
        {
60
            cb_Server->addItem(o_Settings->SERVER.IP[z]);
61
            cb_Server->addItem(o_Settings->SERVER.IP[z]);
61
        }
62
        }
62
    }
63
    }
63
 
64
 
64
    cb_Server->setCurrentIndex(o_Settings->SERVER.IP_ID);
65
    cb_Server->setCurrentIndex(o_Settings->SERVER.IP_ID);
65
 
66
 
66
    le_Password->setText(o_Settings->SERVER.Password);
67
    le_Password->setText(o_Settings->SERVER.Password);
67
 
68
 
68
    sb_Intervall->setValue(o_Settings->DATA.Intervall);
69
    sb_Intervall->setValue(o_Settings->DATA.Intervall);
69
 
70
 
70
    cb_CenterPos->setChecked(o_Settings->CONFIG.cb_CenterPos);
71
    cb_CenterPos->setChecked(o_Settings->CONFIG.cb_CenterPos);
71
    cb_ShowRoute->setChecked(o_Settings->CONFIG.cb_ShowRoute);
72
    cb_ShowRoute->setChecked(o_Settings->CONFIG.cb_ShowRoute);
72
    cb_ShowWPs->setChecked(o_Settings->CONFIG.cb_ShowWPs);
73
    cb_ShowWPs->setChecked(o_Settings->CONFIG.cb_ShowWPs);
73
    cb_Goto->setChecked(o_Settings->CONFIG.cb_Goto);
74
    cb_Goto->setChecked(o_Settings->CONFIG.cb_Goto);
74
 
75
 
75
//    tb_More->addWidget(cb_Maps);
76
//    tb_More->addWidget(cb_Maps);
76
    cb_Maps->setVisible(false);
77
    cb_Maps->setVisible(false);
77
 
78
 
78
    ac_Toolbar->setChecked(o_Settings->GUI.Toolbar);
79
    ac_Toolbar->setChecked(o_Settings->GUI.Toolbar);
79
 
80
 
80
    if (ac_Toolbar->isChecked())
81
    if (ac_Toolbar->isChecked())
81
    {
82
    {
82
        btn_Connect->setVisible(false);
83
        btn_Connect->setVisible(false);
83
    }
84
    }
84
    else
85
    else
85
    {
86
    {
86
        ToolBar->setVisible(false);
87
        ToolBar->setVisible(false);
87
        tb_More->setVisible(false);
88
        tb_More->setVisible(false);
88
    }
89
    }
89
}
90
}
90
 
91
 
91
// Signale mit Slots verbinden
92
// Signale mit Slots verbinden
92
void dlg_Main::init_Connections()
93
void dlg_Main::init_Connections()
93
{
94
{
94
    connect(ac_Connect, SIGNAL(triggered()), this, SLOT(slot_ac_Connect()));
95
    connect(ac_Connect, SIGNAL(triggered()), this, SLOT(slot_ac_Connect()));
95
    connect(ac_Toolbar, SIGNAL(triggered()), this, SLOT(slot_ac_Toolbar()));
96
    connect(ac_Toolbar, SIGNAL(triggered()), this, SLOT(slot_ac_Toolbar()));
96
 
-
 
97
    // About QMK-Kernel & About-QT Dialog einfügen
-
 
98
    connect(ac_About, SIGNAL(triggered()), this, SLOT(slot_ac_About()));
-
 
99
    menu_Help->addAction(trUtf8("Über &Qt"), qApp, SLOT(aboutQt()));
-
 
100
 
97
 
101
    connect(sb_Intervall, SIGNAL(valueChanged(int)), this, SLOT(slot_sb_Intervall(int)));
98
    connect(sb_Intervall, SIGNAL(valueChanged(int)), this, SLOT(slot_sb_Intervall(int)));
102
 
99
 
103
    connect(sl_Zoom,   SIGNAL(valueChanged(int)), this, SLOT(slot_Zoom(int)));
100
    connect(sl_Zoom,   SIGNAL(valueChanged(int)), this, SLOT(slot_Zoom(int)));
104
    connect(cb_Maps,   SIGNAL(currentIndexChanged(int)), this, SLOT(slot_ChangeMap(int)));
101
    connect(cb_Maps,   SIGNAL(currentIndexChanged(int)), this, SLOT(slot_ChangeMap(int)));
105
 
102
 
106
    connect(cb_ShowWPs, SIGNAL(toggled(bool)), this, SLOT(slot_ShowWayPoints(bool)));
103
    connect(cb_ShowWPs, SIGNAL(toggled(bool)), this, SLOT(slot_ShowWayPoints(bool)));
107
 
104
 
108
    connect(btn_WPAdd,    SIGNAL(clicked()), this, SLOT(slot_btn_WPAdd()));
105
    connect(btn_WPAdd,    SIGNAL(clicked()), this, SLOT(slot_btn_WPAdd()));
109
    connect(btn_WPFly,    SIGNAL(clicked()), this, SLOT(slot_btn_WPFly()));
106
    connect(btn_WPFly,    SIGNAL(clicked()), this, SLOT(slot_btn_WPFly()));
110
    connect(btn_WPDelete, SIGNAL(clicked()), this, SLOT(slot_btn_WPDelete()));
107
    connect(btn_WPDelete, SIGNAL(clicked()), this, SLOT(slot_btn_WPDelete()));
111
 
108
 
112
    connect(ac_LoadRoute, SIGNAL(triggered()), this, SLOT(slot_ac_LoadWayPoints()));
109
    connect(ac_LoadRoute, SIGNAL(triggered()), this, SLOT(slot_ac_LoadWayPoints()));
113
    connect(ac_SaveRoute, SIGNAL(triggered()), this, SLOT(slot_ac_SaveRoute()));
110
    connect(ac_SaveRoute, SIGNAL(triggered()), this, SLOT(slot_ac_SaveRoute()));
114
 
111
 
115
    connect(ac_LoadMap,     SIGNAL(triggered()), this, SLOT(slot_ac_LoadMapPic()));
112
    connect(ac_LoadMap,     SIGNAL(triggered()), this, SLOT(slot_ac_LoadMapPic()));
116
    connect(ac_Record,      SIGNAL(triggered()), this, SLOT(slot_ac_Record()));
113
    connect(ac_Record,      SIGNAL(triggered()), this, SLOT(slot_ac_Record()));
117
    connect(ac_RouteDelete, SIGNAL(triggered()), this, SLOT(slot_ac_RouteDelete()));
114
    connect(ac_RouteDelete, SIGNAL(triggered()), this, SLOT(slot_ac_RouteDelete()));
-
 
115
 
-
 
116
    // About QMK-Kernel & About-QT Dialog einfügen
-
 
117
    connect(ac_About, SIGNAL(triggered()), this, SLOT(slot_ac_About()));
-
 
118
    menu_Help->addAction(trUtf8("Über &Qt"), qApp, SLOT(aboutQt()));
118
}
119
}
119
 
120
 
120
void dlg_Main::init_Directorys()
121
void dlg_Main::init_Directorys()
121
{
122
{
122
    QDir *t_Dir = new QDir();
123
    QDir *t_Dir = new QDir();
123
 
124
 
124
    s_Dir.MainData = QDir::homePath() + "/QMK-Data";
125
    s_Dir.MainData = QDir::homePath() + "/QMK-Data";
125
    if (!t_Dir->exists(s_Dir.MainData))
126
    if (!t_Dir->exists(s_Dir.MainData))
126
    {
127
    {
127
        t_Dir->mkdir(s_Dir.MainData);
128
        t_Dir->mkdir(s_Dir.MainData);
128
    }
129
    }
129
 
130
 
130
    s_Dir.MapCache = s_Dir.MainData + "/Map-Cache";
131
    s_Dir.MapCache = s_Dir.MainData + "/Map-Cache";
131
    if (!t_Dir->exists(s_Dir.MapCache))
132
    if (!t_Dir->exists(s_Dir.MapCache))
132
    {
133
    {
133
        t_Dir->mkdir(s_Dir.MapCache);
134
        t_Dir->mkdir(s_Dir.MapCache);
134
    }
135
    }
135
 
136
 
136
    s_Dir.WPRoutes = s_Dir.MainData + "/WP-Routes";
137
    s_Dir.WPRoutes = s_Dir.MainData + "/WP-Routes";
137
    if (!t_Dir->exists(s_Dir.WPRoutes))
138
    if (!t_Dir->exists(s_Dir.WPRoutes))
138
    {
139
    {
139
        t_Dir->mkdir(s_Dir.WPRoutes);
140
        t_Dir->mkdir(s_Dir.WPRoutes);
140
    }
141
    }
141
 
142
 
142
    s_Dir.MapPics = s_Dir.MainData + "/Map-Pics";
143
    s_Dir.MapPics = s_Dir.MainData + "/Map-Pics";
143
    if (!t_Dir->exists(s_Dir.MapPics))
144
    if (!t_Dir->exists(s_Dir.MapPics))
144
    {
145
    {
145
        t_Dir->mkdir(s_Dir.MapPics);
146
        t_Dir->mkdir(s_Dir.MapPics);
146
    }
147
    }
147
 
148
 
148
    s_Dir.Flights = s_Dir.MainData + "/Flights";
149
    s_Dir.Flights = s_Dir.MainData + "/Flights";
149
    if (!t_Dir->exists(s_Dir.Flights))
150
    if (!t_Dir->exists(s_Dir.Flights))
150
    {
151
    {
151
        t_Dir->mkdir(s_Dir.Flights);
152
        t_Dir->mkdir(s_Dir.Flights);
152
    }
153
    }
153
}
154
}
154
 
155
 
155
void dlg_Main::parse_IP_Data(QString t_Data)
156
void dlg_Main::parse_IP_Data(QString t_Data)
156
{
157
{
157
    QStringList Data;
158
    QStringList Data;
158
    Data = t_Data.split(":");
159
    Data = t_Data.split(":");
159
 
160
 
160
    if (Data.count() > 1)
161
    if (Data.count() > 1)
161
    {
162
    {
162
        int CMD = Data[2].toInt();
163
        int CMD = Data[2].toInt();
163
 
164
 
164
        switch(CMD)
165
        switch(CMD)
165
        {
166
        {
166
            case 501 :
167
            case 101 :
-
 
168
            {
-
 
169
                o_Input->send_Data(HandlerIP::make_Frame(ID_MAPS, 101, QA_NAME + " " + QA_VERSION));
-
 
170
            }
-
 
171
            break;
-
 
172
            case 502 :
167
            {
173
            {
-
 
174
                switch (Data[3].toInt())
-
 
175
                {
-
 
176
                    case 105 :
-
 
177
                    {
-
 
178
                        QString s_MD5PW;
-
 
179
                        QByteArray a_MD5PW;
-
 
180
 
-
 
181
                        a_MD5PW = QCryptographicHash::hash(le_Password->text().toAscii(),QCryptographicHash::Md5);
-
 
182
 
-
 
183
                        s_MD5PW = QString(a_MD5PW.toHex().data());
-
 
184
 
-
 
185
                        o_Input->send_Data(HandlerIP::make_Frame(ID_MAPS, 105, s_MD5PW));
-
 
186
                    }
-
 
187
                    break;
-
 
188
                    case 106 :
-
 
189
                    {
168
                o_Input->send_Data(HandlerIP::make_Frame(0, 105, le_Password->text()));
190
                        o_Input->send_Data(HandlerIP::make_Frame(ID_MAPS, 106, DataFields));
-
 
191
                    }
-
 
192
                    break;
-
 
193
                }
169
            }
194
            }
170
            break;
195
            break;
171
            case 505 :
196
            case 505 :
172
            {
197
            {
173
                if (Data[3] == "OK")
198
                if (Data[3] == "OK")
174
                {
199
                {
175
                }
200
                }
176
                else
201
                else
177
                {
202
                {
178
                    QMessageBox::warning(this, QA_NAME, trUtf8("Authentifizierung fehlgeschlagen. <br />Daten senden zum Mikrokopter nicht möglich."), QMessageBox::Ok);
203
                    QMessageBox::warning(this, QA_NAME, trUtf8("Authentifizierung fehlgeschlagen. <br />Daten senden zum Mikrokopter nicht möglich."), QMessageBox::Ok);
179
                }
204
                }
180
            }
205
            }
181
            break;
206
            break;
182
        }
207
        }
183
    }
208
    }
184
}
209
}
185
 
210
 
186
// Eingangsdaten verarbeiten
211
// Eingangsdaten verarbeiten
187
void dlg_Main::parse_MK_Data(QString t_Data)
212
void dlg_Main::parse_MK_Data(QString t_Data)
188
{
213
{
189
    unsigned char OutData[150];
214
    unsigned char OutData[150];
190
    char *InData = t_Data.toLatin1().data();
215
    char *InData = t_Data.toLatin1().data();
191
 
216
 
192
    if (HandlerMK::Decode_64(InData, t_Data.length(), OutData) != 0)
217
    if (HandlerMK::Decode_64(InData, t_Data.length(), OutData) != 0)
193
    {
218
    {
194
 
219
 
195
        switch(InData[2])
220
        switch(InData[2])
196
        {
221
        {
197
            case 'V' : // Versions-Info
222
            case 'V' : // Versions-Info
198
                {
223
                {
199
                    o_Input->stop_Resend(DATA_VERSION);
224
                    o_Input->stop_Resend(DATA_VERSION);
200
                    VersionInfo = HandlerMK::parse_Version(OutData, InData[1] - 'a');
225
                    VersionInfo = HandlerMK::parse_Version(OutData, InData[1] - 'a');
201
                    setWindowTitle(QA_NAME + " " + QA_VERSION + " - " + VersionInfo.Hardware + " " + VersionInfo.Version);
226
                    setWindowTitle(QA_NAME + " " + QA_VERSION + " - " + VersionInfo.Hardware + " " + VersionInfo.Version);
202
 
227
 
203
                    if (VersionInfo.ID == ADDRESS_NC)
228
                    if (VersionInfo.ID == ADDRESS_NC)
204
                    {
229
                    {
205
                        c_Data[0] = sb_Intervall->value() / 10;
230
                        c_Data[0] = sb_Intervall->value() / 10;
206
                        o_Input->send_Data(HandlerMK::make_Frame('o', ADDRESS_ALL, c_Data, 1).toLatin1().data());
231
                        o_Input->send_Data(HandlerMK::make_Frame('o', ADDRESS_ALL, c_Data, 1).toLatin1().data());
207
                    }
232
                    }
208
                    else // TODO: Befehl wenden zum Wechseln auf Navi.
233
                    else // TODO: Befehl wenden zum Wechseln auf Navi.
209
                    {
234
                    {
210
                    }
235
                    }
211
                }
236
                }
212
            break;
237
            break;
213
            case 'O' : // Navi-OSD-Data
238
            case 'O' : // Navi-OSD-Data
214
                {
239
                {
215
                    if (InData[1] - 'a' == ADDRESS_NC)
240
                    if (InData[1] - 'a' == ADDRESS_NC)
216
                    {
241
                    {
217
                        s_MK_NaviData MK_NaviData;
242
                        s_MK_NaviData MK_NaviData;
218
 
243
 
219
                        memcpy((unsigned char *)&MK_NaviData, (unsigned char *)&OutData, sizeof(MK_NaviData));
244
                        memcpy((unsigned char *)&MK_NaviData, (unsigned char *)&OutData, sizeof(MK_NaviData));
220
                        if (MK_NaviData.Version == MK_VERSION_NAVI)
245
                        if (MK_NaviData.Version == MK_VERSION_NAVI)
221
                        {
246
                        {
222
                            show_Data(MK_NaviData);
247
                            show_Data(MK_NaviData);
223
                            add_Position(MK_NaviData);
248
                            add_Position(MK_NaviData);
224
                        }
249
                        }
225
                    }
250
                    }
226
                }
251
                }
227
            break;
252
            break;
228
            case 'W' : // WayPoints
253
            case 'W' : // WayPoints
229
                {
254
                {
230
                    o_Input->stop_Resend(DATA_WRITE_WAYPOINT);
255
                    o_Input->stop_Resend(DATA_WRITE_WAYPOINT);
231
 
256
 
232
                    if (OutData[0] < l_WayPoints.count())
257
                    if (OutData[0] < l_WayPoints.count())
233
                    {
258
                    {
234
                        send_WayPoints(l_WayPoints, OutData[0] + 1);
259
                        send_WayPoints(l_WayPoints, OutData[0] + 1);
235
                    }
260
                    }
236
                }
261
                }
237
            break;
262
            break;
238
        }
263
        }
239
    }
264
    }
240
}
265
}
241
 
266
 
242
///////////////////////////////////////////////////////////////////
267
///////////////////////////////////////////////////////////////////
243
// QMK-Maps                                                      //
268
// QMK-Maps                                                      //
244
///////////////////////////////////////////////////////////////////
269
///////////////////////////////////////////////////////////////////
245
 
270
 
246
void dlg_Main::create_Map()
271
void dlg_Main::create_Map()
247
{
272
{
248
    o_Map->resize(w_Map->size() - QSize(25,50));
273
    o_Map->resize(w_Map->size() - QSize(25,50));
249
    o_Map->enablePersistentCache(s_Dir.MapCache);
274
    o_Map->enablePersistentCache(s_Dir.MapCache);
250
    o_Map->showScale(true);
275
    o_Map->showScale(true);
251
 
276
 
252
    o_Adapter = new OSMMapAdapter();
277
    o_Adapter = new OSMMapAdapter();
253
 
278
 
254
    o_Layer   = new MapLayer("MapLayer", o_Adapter);
279
    o_Layer   = new MapLayer("MapLayer", o_Adapter);
255
    o_Click   = new GeometryLayer("Click", o_Adapter);
280
    o_Click   = new GeometryLayer("Click", o_Adapter);
256
    o_Info    = new GeometryLayer("Poute", o_Adapter);
281
    o_Info    = new GeometryLayer("Poute", o_Adapter);
257
    o_RouteWP = new GeometryLayer("Route-WayPoint", o_Adapter);
282
    o_RouteWP = new GeometryLayer("Route-WayPoint", o_Adapter);
258
    o_RouteFL = new GeometryLayer("Route-Flight", o_Adapter);
283
    o_RouteFL = new GeometryLayer("Route-Flight", o_Adapter);
259
 
284
 
260
    o_Map->addLayer(o_Layer);
285
    o_Map->addLayer(o_Layer);
261
    o_Map->addLayer(o_Click);
286
    o_Map->addLayer(o_Click);
262
    o_Map->addLayer(o_Info);
287
    o_Map->addLayer(o_Info);
263
    o_Map->addLayer(o_RouteWP);
288
    o_Map->addLayer(o_RouteWP);
264
    o_Map->addLayer(o_RouteFL);
289
    o_Map->addLayer(o_RouteFL);
265
 
290
 
266
    o_Map->setZoom(17);
291
    o_Map->setZoom(17);
267
//    o_Map->setView(QPointF(o_Settings->NAVI.Longitude,o_Settings->NAVI.Latitude));
292
//    o_Map->setView(QPointF(o_Settings->NAVI.Longitude,o_Settings->NAVI.Latitude));
268
//    o_Map->setView(QPointF(13.5,52.5));
293
//    o_Map->setView(QPointF(13.5,52.5));
269
    o_Map->setView(QPointF(13.419805,52.431787));
294
    o_Map->setView(QPointF(13.419805,52.431787));
270
    connect(o_Map, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)), this, SLOT(slot_Click(const QMouseEvent*, const QPointF)));
295
    connect(o_Map, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)), this, SLOT(slot_Click(const QMouseEvent*, const QPointF)));
271
 
296
 
272
    l_Map->addWidget(o_Map);
297
    l_Map->addWidget(o_Map);
273
 
298
 
274
    sl_Zoom->setValue(17);
299
    sl_Zoom->setValue(17);
275
 
300
 
276
    // Flight
301
    // Flight
277
    Pen[0] = new QPen(QColor(0,0,255,255));
302
    Pen[0] = new QPen(QColor(0,0,255,255));
278
    Pen[0]->setWidth(2);
303
    Pen[0]->setWidth(2);
279
    Pen[1] = new QPen(QColor(0,0,255,255));
304
    Pen[1] = new QPen(QColor(0,0,255,255));
280
    Pen[1]->setWidth(1);
305
    Pen[1]->setWidth(1);
281
    // WayPoint
306
    // WayPoint
282
    Pen[2] = new QPen(QColor(255,0,0,255));
307
    Pen[2] = new QPen(QColor(255,0,0,255));
283
    Pen[2]->setWidth(2);
308
    Pen[2]->setWidth(2);
284
    Pen[3] = new QPen(QColor(255,0,0,255));
309
    Pen[3] = new QPen(QColor(255,0,0,255));
285
    Pen[3]->setWidth(1);
310
    Pen[3]->setWidth(1);
286
    // Info
311
    // Info
287
    Pen[4] = new QPen(QColor(0,128,128,255));
312
    Pen[4] = new QPen(QColor(0,128,128,255));
288
    Pen[4]->setWidth(2);
313
    Pen[4]->setWidth(2);
289
    Pen[5] = new QPen(QColor(0,128,128,255));
314
    Pen[5] = new QPen(QColor(0,128,128,255));
290
    Pen[5]->setWidth(1);
315
    Pen[5]->setWidth(1);
291
}
316
}
292
 
317
 
293
// auf Veränderung der Fenstergröße reagieren
318
// auf Veränderung der Fenstergröße reagieren
294
void dlg_Main::resizeEvent ( QResizeEvent * event )
319
void dlg_Main::resizeEvent ( QResizeEvent * event )
295
{
320
{
296
    event = event;
321
    event = event;
297
    o_Map->resize(w_Map->size() - QSize(25,25));
322
    o_Map->resize(w_Map->size() - QSize(25,25));
298
}
323
}
299
 
324
 
300
void dlg_Main::wheelEvent(QWheelEvent *event)
325
void dlg_Main::wheelEvent(QWheelEvent *event)
301
{
326
{
302
    int zoomValue = sl_Zoom->value();
327
    int zoomValue = sl_Zoom->value();
303
    int numDegrees = event->delta() / 8;
328
    int numDegrees = event->delta() / 8;
304
    int numSteps = numDegrees / 15;
329
    int numSteps = numDegrees / 15;
305
    zoomValue += numSteps;
330
    zoomValue += numSteps;
306
    if (zoomValue < 0) { zoomValue = 0;}
331
    if (zoomValue < 0) { zoomValue = 0;}
307
    if (zoomValue > 17) { zoomValue = 17;}
332
    if (zoomValue > 17) { zoomValue = 17;}
308
    sl_Zoom->setValue(zoomValue);
333
    sl_Zoom->setValue(zoomValue);
309
}
334
}
310
 
335
 
311
QList<sWayPoint> dlg_Main::parse_WayPointKML(QString s_File)
336
QList<sWayPoint> dlg_Main::parse_WayPointKML(QString s_File)
312
{
337
{
313
    QList<sWayPoint> tmp_WayPoints;
338
    QList<sWayPoint> tmp_WayPoints;
314
    sWayPoint tmp_WayPoint;
339
    sWayPoint tmp_WayPoint;
315
 
340
 
316
    QFile f_KML(s_File);
341
    QFile f_KML(s_File);
317
    f_KML.open(QIODevice::ReadOnly | QIODevice::Text);
342
    f_KML.open(QIODevice::ReadOnly | QIODevice::Text);
318
 
343
 
319
    QByteArray s_KML;
344
    QByteArray s_KML;
320
 
345
 
321
    while (!f_KML.atEnd())
346
    while (!f_KML.atEnd())
322
    {
347
    {
323
        s_KML.append(f_KML.readLine());
348
        s_KML.append(f_KML.readLine());
324
     }
349
     }
325
 
350
 
326
    f_KML.close();
351
    f_KML.close();
327
 
352
 
328
    QDomDocument *UserXML;
353
    QDomDocument *UserXML;
329
    UserXML = new QDomDocument;
354
    UserXML = new QDomDocument;
330
 
355
 
331
    UserXML->setContent(s_KML);
356
    UserXML->setContent(s_KML);
332
 
357
 
333
    QDomElement Root       = UserXML->firstChildElement("kml");
358
    QDomElement Root       = UserXML->firstChildElement("kml");
334
    QDomElement Document   = Root.firstChildElement("Document");
359
    QDomElement Document   = Root.firstChildElement("Document");
335
    QDomElement Placemark  = Document.firstChildElement("Placemark");
360
    QDomElement Placemark  = Document.firstChildElement("Placemark");
336
    QDomElement Linestring = Placemark.firstChildElement("LineString");
361
    QDomElement Linestring = Placemark.firstChildElement("LineString");
337
 
362
 
338
    QString Name = Placemark.firstChildElement("name").toElement().text();
363
    QString Name = Placemark.firstChildElement("name").toElement().text();
339
 
364
 
340
    QString Route = Linestring.firstChildElement("coordinates").toElement().text();
365
    QString Route = Linestring.firstChildElement("coordinates").toElement().text();
341
 
366
 
342
    QStringList s_Points = Route.split(" ");
367
    QStringList s_Points = Route.split(" ");
343
 
368
 
344
    QStringList Position;
369
    QStringList Position;
345
 
370
 
346
    for (int z = 0; z < s_Points.count() - 1; z++)
371
    for (int z = 0; z < s_Points.count() - 1; z++)
347
    {
372
    {
348
        if (z != 20)
373
        if (z != 20)
349
        {
374
        {
350
           Position = s_Points[z].split(",");
375
           Position = s_Points[z].split(",");
351
           tmp_WayPoint.Longitude = Position[0].toDouble();
376
           tmp_WayPoint.Longitude = Position[0].toDouble();
352
           tmp_WayPoint.Latitude  = Position[1].toDouble();
377
           tmp_WayPoint.Latitude  = Position[1].toDouble();
353
           tmp_WayPoint.Altitude  = Position[2].toDouble();
378
           tmp_WayPoint.Altitude  = Position[2].toDouble();
354
           tmp_WayPoint.Time      = sb_Time->value();
379
           tmp_WayPoint.Time      = sb_Time->value();
355
 
380
 
356
           tmp_WayPoints.append(tmp_WayPoint);
381
           tmp_WayPoints.append(tmp_WayPoint);
357
        }
382
        }
358
        else
383
        else
359
        {
384
        {
360
            QMessageBox::warning(this, QA_NAME,trUtf8("Die Wegpunkt-Liste umfasst mehr als 20 Einträge. Es werden nur die ersten 20 Einträge übernommen."), QMessageBox::Ok);
385
            QMessageBox::warning(this, QA_NAME,trUtf8("Die Wegpunkt-Liste umfasst mehr als 20 Einträge. Es werden nur die ersten 20 Einträge übernommen."), QMessageBox::Ok);
361
 
386
 
362
            btn_WPAdd->setEnabled(false);
387
            btn_WPAdd->setEnabled(false);
363
 
388
 
364
            z = s_Points.count();
389
            z = s_Points.count();
365
        }
390
        }
366
    }
391
    }
367
    return tmp_WayPoints;
392
    return tmp_WayPoints;
368
}
393
}
369
 
394
 
370
QList<sWayPoint> dlg_Main::parse_WayPointMKW(QString s_File)
395
QList<sWayPoint> dlg_Main::parse_WayPointMKW(QString s_File)
371
{
396
{
372
    QList<sWayPoint> tmp_WayPoints;
397
    QList<sWayPoint> tmp_WayPoints;
373
    sWayPoint tmp_WayPoint;
398
    sWayPoint tmp_WayPoint;
374
 
399
 
375
    QFile f_MKW(s_File);
400
    QFile f_MKW(s_File);
376
    f_MKW.open(QIODevice::ReadOnly | QIODevice::Text);
401
    f_MKW.open(QIODevice::ReadOnly | QIODevice::Text);
377
 
402
 
378
    QString s_MKW;
403
    QString s_MKW;
379
 
404
 
380
    while (!f_MKW.atEnd())
405
    while (!f_MKW.atEnd())
381
    {
406
    {
382
        s_MKW.append(f_MKW.readLine());
407
        s_MKW.append(f_MKW.readLine());
383
     }
408
     }
384
 
409
 
385
    f_MKW.close();
410
    f_MKW.close();
386
 
411
 
387
    QStringList s_Points = s_MKW.split(" ");
412
    QStringList s_Points = s_MKW.split(" ");
388
 
413
 
389
    QStringList Position;
414
    QStringList Position;
390
 
415
 
391
    for (int z = 0; z < s_Points.count() - 1; z++)
416
    for (int z = 0; z < s_Points.count() - 1; z++)
392
    {
417
    {
393
        if (z != 20)
418
        if (z != 20)
394
        {
419
        {
395
           Position = s_Points[z].split(",");
420
           Position = s_Points[z].split(",");
396
           tmp_WayPoint.Longitude = Position[0].toDouble();
421
           tmp_WayPoint.Longitude = Position[0].toDouble();
397
           tmp_WayPoint.Latitude  = Position[1].toDouble();
422
           tmp_WayPoint.Latitude  = Position[1].toDouble();
398
           tmp_WayPoint.Altitude  = Position[2].toDouble();
423
           tmp_WayPoint.Altitude  = Position[2].toDouble();
399
           tmp_WayPoint.Time      = Position[3].toInt();
424
           tmp_WayPoint.Time      = Position[3].toInt();
400
 
425
 
401
           tmp_WayPoints.append(tmp_WayPoint);
426
           tmp_WayPoints.append(tmp_WayPoint);
402
        }
427
        }
403
        else
428
        else
404
        {
429
        {
405
            QMessageBox::warning(this, QA_NAME,trUtf8("Die Wegpunkt-Liste umfasst mehr als 20 Einträge. Es werden nur die ersten 20 Einträge übernommen."), QMessageBox::Ok);
430
            QMessageBox::warning(this, QA_NAME,trUtf8("Die Wegpunkt-Liste umfasst mehr als 20 Einträge. Es werden nur die ersten 20 Einträge übernommen."), QMessageBox::Ok);
406
 
431
 
407
            btn_WPAdd->setEnabled(false);
432
            btn_WPAdd->setEnabled(false);
408
 
433
 
409
            z = s_Points.count();
434
            z = s_Points.count();
410
        }
435
        }
411
    }
436
    }
412
    return tmp_WayPoints;
437
    return tmp_WayPoints;
413
}
438
}
414
 
439
 
415
// Waypoint-Route anzeigen in Karte
440
// Waypoint-Route anzeigen in Karte
416
void dlg_Main::show_WayPoints(QList<sWayPoint> WayPoints)
441
void dlg_Main::show_WayPoints(QList<sWayPoint> WayPoints)
417
{
442
{
418
    Point* p_Point;
443
    Point* p_Point;
419
 
444
 
420
    o_RouteWP->removeGeometry(l_RouteWP);
445
    o_RouteWP->removeGeometry(l_RouteWP);
421
    p_RouteWP.clear();
446
    p_RouteWP.clear();
422
    l_WayPoints.clear();
447
    l_WayPoints.clear();
423
 
448
 
424
    l_WayPoints = WayPoints;
449
    l_WayPoints = WayPoints;
425
 
450
 
426
    for (int z = 0; z < WayPoints.count(); z++)
451
    for (int z = 0; z < WayPoints.count(); z++)
427
    {
452
    {
428
        p_Point = new Point(WayPoints[z].Longitude, WayPoints[z].Latitude);
453
        p_Point = new Point(WayPoints[z].Longitude, WayPoints[z].Latitude);
429
 
454
 
430
        p_RouteWP.append(p_Point);
455
        p_RouteWP.append(p_Point);
431
    }
456
    }
432
 
457
 
433
    l_RouteWP = new LineString(p_RouteWP, "", Pen[3]);
458
    l_RouteWP = new LineString(p_RouteWP, "", Pen[3]);
434
    o_RouteWP->addGeometry(l_RouteWP);
459
    o_RouteWP->addGeometry(l_RouteWP);
435
 
460
 
436
    o_Map->setView(p_Point);
461
    o_Map->setView(p_Point);
437
 
462
 
438
    o_Map->updateRequestNew();
463
    o_Map->updateRequestNew();
439
}
464
}
440
 
465
 
441
// Waypoint-Liste speichern
466
// Waypoint-Liste speichern
442
void dlg_Main::save_WayPointsMKW(QString s_File)
467
void dlg_Main::save_WayPointsMKW(QString s_File)
443
{
468
{
444
    QFile *f_MKW = new QFile(s_File);
469
    QFile *f_MKW = new QFile(s_File);
445
 
470
 
446
    f_MKW->open(QIODevice::ReadWrite | QIODevice::Text);
471
    f_MKW->open(QIODevice::ReadWrite | QIODevice::Text);
447
 
472
 
448
    QTextStream out(f_MKW);
473
    QTextStream out(f_MKW);
449
 
474
 
450
    out.setRealNumberPrecision(9);
475
    out.setRealNumberPrecision(9);
451
 
476
 
452
    for (int z = 0; z < l_WayPoints.count(); z++)
477
    for (int z = 0; z < l_WayPoints.count(); z++)
453
    {
478
    {
454
        out << l_WayPoints[z].Longitude << "," << l_WayPoints[z].Latitude << "," << l_WayPoints[z].Altitude << "," << l_WayPoints[z].Time << " \n";
479
        out << l_WayPoints[z].Longitude << "," << l_WayPoints[z].Latitude << "," << l_WayPoints[z].Altitude << "," << l_WayPoints[z].Time << " \n";
455
    }
480
    }
456
 
481
 
457
    f_MKW->close();
482
    f_MKW->close();
458
}
483
}
459
 
484
 
460
void dlg_Main::show_Data(s_MK_NaviData t_NaviData)
485
void dlg_Main::show_Data(s_MK_NaviData t_NaviData)
461
{
486
{
462
    QString Mode = "NC-Flags : ";
487
    QString Mode = "NC-Flags : ";
463
    if (t_NaviData.NCFlags &  0x08) {le_Mode->setText(tr("Range Limit")); Mode += "R";}
488
    if (t_NaviData.NCFlags &  0x08) {le_Mode->setText(tr("Range Limit")); Mode += "R";}
464
    if (t_NaviData.NCFlags &  0x10) {le_Mode->setText(tr("Serial Error")); Mode += "S";}
489
    if (t_NaviData.NCFlags &  0x10) {le_Mode->setText(tr("Serial Error")); Mode += "S";}
465
    if (t_NaviData.NCFlags &  0x20) {le_Mode->setText(tr("Target reached")); Mode += "T";}
490
    if (t_NaviData.NCFlags &  0x20) {le_Mode->setText(tr("Target reached")); Mode += "T";}
466
    if (t_NaviData.NCFlags &  0x40) {le_Mode->setText(tr("Manual Control")); Mode += "M";}
491
    if (t_NaviData.NCFlags &  0x40) {le_Mode->setText(tr("Manual Control")); Mode += "M";}
467
    if (t_NaviData.NCFlags &  0x01) {le_Mode->setText(tr("Free")); Mode += "F";}
492
    if (t_NaviData.NCFlags &  0x01) {le_Mode->setText(tr("Free")); Mode += "F";}
468
    if (t_NaviData.NCFlags &  0x02) {le_Mode->setText(tr("Position Hold")); Mode += "P";}
493
    if (t_NaviData.NCFlags &  0x02) {le_Mode->setText(tr("Position Hold")); Mode += "P";}
469
    if (t_NaviData.NCFlags &  0x04) {le_Mode->setText(tr("Coming Home")); Mode += "C";}
494
    if (t_NaviData.NCFlags &  0x04) {le_Mode->setText(tr("Coming Home")); Mode += "C";}
470
 
495
 
471
    //qDebug(Mode.toLatin1().data());
496
    //qDebug(Mode.toLatin1().data());
472
 
497
 
473
    le_WP->setText(QString("%1/").arg(t_NaviData.WaypointIndex) + QString("%1").arg(t_NaviData.WaypointNumber));
498
    le_WP->setText(QString("%1/").arg(t_NaviData.WaypointIndex) + QString("%1").arg(t_NaviData.WaypointNumber));
474
    le_WPTime->setText(QString("%1:").arg(t_NaviData.TargetHoldTime / 60) + (QString("%1").arg(t_NaviData.TargetHoldTime % 60)).rightJustified(2, '0'));
499
    le_WPTime->setText(QString("%1:").arg(t_NaviData.TargetHoldTime / 60) + (QString("%1").arg(t_NaviData.TargetHoldTime % 60)).rightJustified(2, '0'));
475
    le_WPDist->setText(QString("%1m").arg(t_NaviData.TargetPositionDeviation.Distance / 10));
500
    le_WPDist->setText(QString("%1m").arg(t_NaviData.TargetPositionDeviation.Distance / 10));
476
    le_HomeDist->setText(QString("%1m").arg(t_NaviData.HomePositionDeviation.Distance / 10));
501
    le_HomeDist->setText(QString("%1m").arg(t_NaviData.HomePositionDeviation.Distance / 10));
477
}
502
}
478
 
503
 
479
// Aktuelle MK-Position hinzufügen
504
// Aktuelle MK-Position hinzufügen
480
void dlg_Main::add_Position(s_MK_NaviData t_NaviData)
505
void dlg_Main::add_Position(s_MK_NaviData t_NaviData)
481
{
506
{
482
    sWayPoint WayPoint;
507
    sWayPoint WayPoint;
483
 
508
 
484
    WayPoint.Longitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Longitude, 7);
509
    WayPoint.Longitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Longitude, 7);
485
    WayPoint.Latitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Latitude, 7);
510
    WayPoint.Latitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Latitude, 7);
486
    WayPoint.Altitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Altitude, 3);
511
    WayPoint.Altitude = HandlerMK::Int2Double(t_NaviData.CurrentPosition.Altitude, 3);
487
 
512
 
488
    o_Settings->NAVI.Latitude  = WayPoint.Latitude;
513
    o_Settings->NAVI.Latitude  = WayPoint.Latitude;
489
    o_Settings->NAVI.Longitude = WayPoint.Longitude;
514
    o_Settings->NAVI.Longitude = WayPoint.Longitude;
490
 
515
 
491
    l_Track.append(WayPoint);
516
    l_Track.append(WayPoint);
492
 
517
 
493
    o_RouteFL->removeGeometry(l_RouteFL);
518
    o_RouteFL->removeGeometry(l_RouteFL);
494
    p_RouteFL.append(new Point(WayPoint.Longitude, WayPoint.Latitude));
519
    p_RouteFL.append(new Point(WayPoint.Longitude, WayPoint.Latitude));
495
 
520
 
496
    o_Click->removeGeometry(LastPos);
521
    o_Click->removeGeometry(LastPos);
497
 
522
 
498
    Point* P = new CirclePoint(WayPoint.Longitude, WayPoint.Latitude, "P1", Point::Middle, Pen[0]);
523
    Point* P = new CirclePoint(WayPoint.Longitude, WayPoint.Latitude, "P1", Point::Middle, Pen[0]);
499
    LastPos = P;
524
    LastPos = P;
500
//    P->setBaselevel(17);
525
//    P->setBaselevel(17);
501
    o_Click->addGeometry(P);
526
    o_Click->addGeometry(P);
502
 
527
 
503
    // Target anzeigen
528
    // Target anzeigen
504
    o_Click->removeGeometry(Target);
529
    o_Click->removeGeometry(Target);
505
 
530
 
506
    Target = new ImagePoint( HandlerMK::Int2Double(t_NaviData.TargetPosition.Longitude, 7), HandlerMK::Int2Double(t_NaviData.TargetPosition.Latitude, 7), ":/Flags/Global/Images/Flags/Target.png", "Start");
531
    Target = new ImagePoint( HandlerMK::Int2Double(t_NaviData.TargetPosition.Longitude, 7), HandlerMK::Int2Double(t_NaviData.TargetPosition.Latitude, 7), ":/Flags/Global/Images/Flags/Target.png", "Start");
507
    Target->setBaselevel(o_Adapter->adaptedZoom());
532
    Target->setBaselevel(o_Adapter->adaptedZoom());
508
    o_Click->addGeometry(Target);
533
    o_Click->addGeometry(Target);
509
 
534
 
510
    if (cb_CenterPos->isChecked())
535
    if (cb_CenterPos->isChecked())
511
    {
536
    {
512
        o_Map->setView(QPointF(WayPoint.Longitude, WayPoint.Latitude));
537
        o_Map->setView(QPointF(WayPoint.Longitude, WayPoint.Latitude));
513
    }
538
    }
514
 
539
 
515
    if (cb_ShowRoute->isChecked())
540
    if (cb_ShowRoute->isChecked())
516
    {
541
    {
517
        l_RouteFL = new LineString(p_RouteFL, "", Pen[1]);
542
        l_RouteFL = new LineString(p_RouteFL, "", Pen[1]);
518
 
543
 
519
        o_RouteFL->addGeometry(l_RouteFL);
544
        o_RouteFL->addGeometry(l_RouteFL);
520
    }
545
    }
521
    o_Map->updateRequestNew();
546
    o_Map->updateRequestNew();
522
 
547
 
523
    if (ac_Record->isChecked())
548
    if (ac_Record->isChecked())
524
    {
549
    {
525
        QTextStream Out(o_Record);
550
        QTextStream Out(o_Record);
526
 
551
 
527
        Out.setRealNumberPrecision(9);
552
        Out.setRealNumberPrecision(9);
528
 
553
 
529
        Out << WayPoint.Longitude << ", " << WayPoint.Latitude << ", " << WayPoint.Altitude << "\n";
554
        Out << WayPoint.Longitude << ", " << WayPoint.Latitude << ", " << WayPoint.Altitude << "\n";
530
    }
555
    }
531
}
556
}
532
 
557
 
533
// Ein Ziel anfliegen.
558
// Ein Ziel anfliegen.
534
// TODO: Check auf  Entfernung zur IST-Position.
559
// TODO: Check auf  Entfernung zur IST-Position.
535
void dlg_Main::send_Target(Point *t_Target)
560
void dlg_Main::send_Target(Point *t_Target)
536
{
561
{
537
    if (l_Track.length() > 0)
562
    if (l_Track.count() > 0)
538
    {
563
    {
539
        s_MK_WayPoint s_WayPoint;
564
        s_MK_WayPoint s_WayPoint;
540
 
565
 
541
        s_WayPoint.Position.Latitude  = int32_t(t_Target->latitude() * 10000000+0.5);
566
        s_WayPoint.Position.Latitude  = int32_t(t_Target->latitude() * 10000000+0.5);
542
        s_WayPoint.Position.Longitude = int32_t(t_Target->longitude() * 10000000+0.5);
567
        s_WayPoint.Position.Longitude = int32_t(t_Target->longitude() * 10000000+0.5);
543
        s_WayPoint.Position.Altitude  = 0;
568
        s_WayPoint.Position.Altitude  = 0;
544
        s_WayPoint.Position.Status    = NEWDATA;
569
        s_WayPoint.Position.Status    = NEWDATA;
545
        s_WayPoint.Heading            = -1;
570
        s_WayPoint.Heading            = -1;
546
        s_WayPoint.ToleranceRadius    = 5;
571
        s_WayPoint.ToleranceRadius    = 5;
547
        s_WayPoint.HoldTime           = sb_Time->value();
572
        s_WayPoint.HoldTime           = sb_Time->value();
548
        s_WayPoint.Event_Flag         = 0;
573
        s_WayPoint.Event_Flag         = 0;
549
        s_WayPoint.reserve[0]         = 0; // reserve
574
        s_WayPoint.reserve[0]         = 0; // reserve
550
        s_WayPoint.reserve[1]         = 0; // reserve
575
        s_WayPoint.reserve[1]         = 0; // reserve
551
        s_WayPoint.reserve[2]         = 0; // reserve
576
        s_WayPoint.reserve[2]         = 0; // reserve
552
        s_WayPoint.reserve[3]         = 0;
577
        s_WayPoint.reserve[3]         = 0;
553
 
578
 
554
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
579
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
555
        o_Input->send_Data(HandlerMK::make_Frame('s', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data());
580
        o_Input->send_Data(HandlerMK::make_Frame('s', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data());
556
    }
581
    }
557
    else
582
    else
558
    {
583
    {
559
        QMessageBox::warning(this, QA_NAME,tr("Es wurden noch keine aktuellen Positionsdaten vom Mikrokopter empfangen."), QMessageBox::Ok);
584
        QMessageBox::warning(this, QA_NAME,tr("Es wurden noch keine aktuellen Positionsdaten vom Mikrokopter empfangen."), QMessageBox::Ok);
560
    }
585
    }
561
}
586
}
562
 
587
 
563
//Waypoint-Liste zum MK senden
588
//Waypoint-Liste zum MK senden
564
void dlg_Main::send_WayPoints(QList<sWayPoint> t_WayPoints, int t_Pos)
589
void dlg_Main::send_WayPoints(QList<sWayPoint> t_WayPoints, int t_Pos)
565
{
590
{
566
    s_MK_WayPoint s_WayPoint;
591
    s_MK_WayPoint s_WayPoint;
567
    double Longitude, Latitude;
592
    double Longitude, Latitude;
568
 
593
 
569
    if (t_Pos == 0)
594
    if (t_Pos == 0)
570
    {   // Waypoint-Liste löschen
595
    {   // Waypoint-Liste löschen
571
        s_WayPoint.Position.Status = INVALID;
596
        s_WayPoint.Position.Status = INVALID;
572
 
597
 
573
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
598
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
574
        o_Input->send_Data(HandlerMK::make_Frame('w', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data(), DATA_WRITE_WAYPOINT);
599
        o_Input->send_Data(HandlerMK::make_Frame('w', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data(), DATA_WRITE_WAYPOINT);
575
    }
600
    }
576
    else
601
    else
577
    {
602
    {
578
        int z = t_Pos - 1;
603
        int z = t_Pos - 1;
579
        Longitude = t_WayPoints[z].Longitude;
604
        Longitude = t_WayPoints[z].Longitude;
580
        Latitude  = t_WayPoints[z].Latitude;
605
        Latitude  = t_WayPoints[z].Latitude;
581
 
606
 
582
        if (Longitude < 100)
607
        if (Longitude < 100)
583
            Longitude *= 10000000+0.5;
608
            Longitude *= 10000000+0.5;
584
 
609
 
585
        if (Latitude < 100)
610
        if (Latitude < 100)
586
            Latitude *= 10000000+0.5;
611
            Latitude *= 10000000+0.5;
587
 
612
 
588
        //fülle Wegpunkt-Daten
613
        //fülle Wegpunkt-Daten
589
        s_WayPoint.Position.Altitude = 0;
614
        s_WayPoint.Position.Altitude = 0;
590
        s_WayPoint.Position.Longitude = int32_t(Longitude);
615
        s_WayPoint.Position.Longitude = int32_t(Longitude);
591
        s_WayPoint.Position.Latitude =  int32_t(Latitude);
616
        s_WayPoint.Position.Latitude =  int32_t(Latitude);
592
        s_WayPoint.Position.Status = NEWDATA;
617
        s_WayPoint.Position.Status = NEWDATA;
593
        s_WayPoint.Heading = -1;
618
        s_WayPoint.Heading = -1;
594
        s_WayPoint.ToleranceRadius = 5;
619
        s_WayPoint.ToleranceRadius = 5;
595
        s_WayPoint.HoldTime = t_WayPoints[z].Time;
620
        s_WayPoint.HoldTime = t_WayPoints[z].Time;
596
        s_WayPoint.Event_Flag = 0;
621
        s_WayPoint.Event_Flag = 0;
597
        s_WayPoint.reserve[0] = 0; // reserve
622
        s_WayPoint.reserve[0] = 0; // reserve
598
        s_WayPoint.reserve[1] = 0; // reserve
623
        s_WayPoint.reserve[1] = 0; // reserve
599
        s_WayPoint.reserve[2] = 0; // reserve
624
        s_WayPoint.reserve[2] = 0; // reserve
600
        s_WayPoint.reserve[3] = 0; // reserve
625
        s_WayPoint.reserve[3] = 0; // reserve
601
 
626
 
602
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
627
        memcpy((unsigned char *)&c_Data, (unsigned char *)&s_WayPoint, sizeof(s_WayPoint));
603
        o_Input->send_Data(HandlerMK::make_Frame('w', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data(), DATA_WRITE_WAYPOINT);
628
        o_Input->send_Data(HandlerMK::make_Frame('w', ADDRESS_NC, c_Data, sizeof(s_WayPoint)).toLatin1().data(), DATA_WRITE_WAYPOINT);
604
    }
629
    }
605
}
630
}
606
 
631
 
607
///////////
632
///////////
608
// Slots //
633
// Slots //
609
///////////
634
///////////
610
 
635
 
611
// About-Dialog
636
// About-Dialog
612
void dlg_Main::slot_ac_About()
637
void dlg_Main::slot_ac_About()
613
{
638
{
614
    QMessageBox::about(this, trUtf8(("Über ")) + QA_NAME, QA_ABOUT);
639
    QMessageBox::about(this, trUtf8(("Über ")) + QA_NAME, QA_ABOUT);
615
}
640
}
616
 
641
 
617
void dlg_Main::slot_ac_Toolbar()
642
void dlg_Main::slot_ac_Toolbar()
618
{
643
{
619
    if (ac_Toolbar->isChecked())
644
    if (ac_Toolbar->isChecked())
620
    {
645
    {
621
        btn_Connect->setVisible(false);
646
        btn_Connect->setVisible(false);
622
        ToolBar->setVisible(true);
647
        ToolBar->setVisible(true);
623
        tb_More->setVisible(true);
648
        tb_More->setVisible(true);
624
    }
649
    }
625
    else
650
    else
626
    {
651
    {
627
        btn_Connect->setVisible(true);
652
        btn_Connect->setVisible(true);
628
        ToolBar->setVisible(false);
653
        ToolBar->setVisible(false);
629
        tb_More->setVisible(false);
654
        tb_More->setVisible(false);
630
    }
655
    }
631
}
656
}
632
 
657
 
633
 
658
 
634
// Datenintervall geändert.
659
// Datenintervall geändert.
635
void dlg_Main::slot_sb_Intervall(int t_Intervall)
660
void dlg_Main::slot_sb_Intervall(int t_Intervall)
636
{
661
{
637
    if (t_Intervall == 0)
662
    if (t_Intervall == 0)
638
    {
663
    {
639
        c_Data[0] = 0;
664
        c_Data[0] = 0;
640
    }
665
    }
641
    else
666
    else
642
    {
667
    {
643
        c_Data[0] = t_Intervall / 10;
668
        c_Data[0] = t_Intervall / 10;
644
    }
669
    }
645
    o_Input->send_Data(HandlerMK::make_Frame('o', ADDRESS_ALL, c_Data, 1).toLatin1().data());
670
    o_Input->send_Data(HandlerMK::make_Frame('o', ADDRESS_ALL, c_Data, 1).toLatin1().data());
646
}
671
}
647
 
672
 
648
// Verbindung zum Server auf    f_Settings = new wdg_Settings( this );bauen
673
// Verbindung zum Server auf    f_Settings = new wdg_Settings( this );bauen
649
void dlg_Main::slot_ac_Connect()
674
void dlg_Main::slot_ac_Connect()
650
{
675
{
651
    if (!o_Input->IsOpen())
676
    if (!o_Input->IsOpen())
652
    {
677
    {
653
        if (cb_Server->findText(cb_Server->currentText()) == -1)
678
        if (cb_Server->findText(cb_Server->currentText()) == -1)
654
        {
679
        {
655
            cb_Server->addItem(cb_Server->currentText());
680
            cb_Server->addItem(cb_Server->currentText());
656
            cb_Server->setCurrentIndex(cb_Server->findText(cb_Server->currentText()));
681
            cb_Server->setCurrentIndex(cb_Server->findText(cb_Server->currentText()));
657
        }
682
        }
658
 
683
 
659
        cb_Server->setEnabled(false);
684
        cb_Server->setEnabled(false);
660
        le_Password->setEnabled(false);
685
        le_Password->setEnabled(false);
661
 
686
 
662
        if (cb_Server->currentText().startsWith('/'))
687
        if (cb_Server->currentText().startsWith('/'))
663
        {
688
        {
664
            o_Input = new Input_TTY();
689
            o_Input = new Input_TTY();
665
            o_Input->Init();
690
            o_Input->Init();
666
 
691
 
667
            set_Input s_Input;
692
            set_Input s_Input;
668
            s_Input.Main = cb_Server->currentText();
693
            s_Input.Main = cb_Server->currentText();
669
 
694
 
670
            if (o_Input->Open(s_Input) == true)
695
            if (o_Input->Open(s_Input) == true)
671
            {
696
            {
672
                ac_Connect->setText(tr("Trennen"));
697
                ac_Connect->setText(tr("Trennen"));
673
                connect(o_Input, SIGNAL(sig_NewData(QString)), this, SLOT(slot_Input_Data(QString)));
698
                connect(o_Input, SIGNAL(sig_NewData(QString)), this, SLOT(slot_Input_Data(QString)));
674
 
699
 
675
                o_Input->send_Data(HandlerMK::make_Frame('v', 0, c_Data, 0).toLatin1().data(), DATA_VERSION);
700
                o_Input->send_Data(HandlerMK::make_Frame('v', 0, c_Data, 0).toLatin1().data(), DATA_VERSION);
676
            }
701
            }
677
            else
702
            else
678
            {
703
            {
679
                cb_Server->setEnabled(true);
704
                cb_Server->setEnabled(true);
680
                le_Password->setEnabled(true);
705
                le_Password->setEnabled(true);
681
            }
706
            }
682
 
707
 
683
        }
708
        }
684
        else
709
        else //  Connect über TCPIP
685
        {
710
        {
686
            o_Input = new Input_TCP();
711
            o_Input = new Input_TCP();
687
            o_Input->Init();
712
            o_Input->Init();
688
 
713
 
689
            set_Input s_Input;
714
            set_Input s_Input;
690
 
715
 
691
            QStringList Server = cb_Server->currentText().split(":");
716
            QStringList Server = cb_Server->currentText().split(":");
692
 
717
 
693
            s_Input.Main = Server[0];
718
            s_Input.Main = Server[0];
694
            s_Input.Sub  = Server[1];
719
            s_Input.Sub  = Server[1];
695
 
720
 
696
            if (o_Input->Open(s_Input) == true)
721
            if (o_Input->Open(s_Input) == true)
697
            {
722
            {
698
                connect(o_Input, SIGNAL(sig_Disconnected(int)), this, SLOT(slot_Input_Disconnected(int)));
723
                connect(o_Input, SIGNAL(sig_Disconnected(int)), this, SLOT(slot_Input_Disconnected(int)));
699
                connect(o_Input, SIGNAL(sig_Connected()), this, SLOT(slot_Input_Connected()));
724
                connect(o_Input, SIGNAL(sig_Connected()), this, SLOT(slot_Input_Connected()));
700
            }
725
            }
701
        }
726
        }
702
    }
727
    }
703
    else
728
    else
704
    {
729
    {
705
        cb_Server->setEnabled(true);
730
        cb_Server->setEnabled(true);
706
        le_Password->setEnabled(true);
731
        le_Password->setEnabled(true);
707
 
732
 
708
        ac_Connect->setText(tr("Verbinden"));
733
        ac_Connect->setText(tr("Verbinden"));
709
        o_Input->Close();
734
        o_Input->Close();
710
        disconnect(o_Input, SIGNAL(sig_NewData(QString)), 0, 0);
735
        disconnect(o_Input, SIGNAL(sig_NewData(QString)), 0, 0);
711
        if (o_Input->Mode() == TCP)
736
        if (o_Input->Mode() == TCP)
712
        {
737
        {
713
            disconnect(o_Input, SIGNAL(sig_Disconnected(int)), 0, 0);
738
            disconnect(o_Input, SIGNAL(sig_Disconnected(int)), 0, 0);
714
            disconnect(o_Input, SIGNAL(sig_Connected()), 0, 0);
739
            disconnect(o_Input, SIGNAL(sig_Connected()), 0, 0);
715
        }
740
        }
716
    }
741
    }
717
}
742
}
718
 
743
 
719
// Neue Daten empfangen.
744
// Neue Daten empfangen.
720
void dlg_Main::slot_Input_Data(QString t_Data)
745
void dlg_Main::slot_Input_Data(QString t_Data)
721
{
746
{
722
    if ((t_Data[0] == '#'))
747
    if ((t_Data[0] == '#'))
723
    {
748
    {
724
        if ((HandlerMK::Check_CRC(t_Data.toLatin1().data(), t_Data.length() - 1)) || ((o_Input->Mode() == TTY) && (HandlerMK::Check_CRC(t_Data.toLatin1().data(), t_Data.length()))))
749
        if ((HandlerMK::Check_CRC(t_Data.toLatin1().data(), t_Data.length() - 1)) || ((o_Input->Mode() == TTY) && (HandlerMK::Check_CRC(t_Data.toLatin1().data(), t_Data.length()))))
725
        {
750
        {
726
            parse_MK_Data(t_Data);
751
            parse_MK_Data(t_Data);
727
        }
752
        }
728
        else
753
        else
729
        {
754
        {
730
//            qDebug(QString("CRC-Error - " + t_Data).toLatin1().data());
755
//            qDebug(QString("CRC-Error - " + t_Data).toLatin1().data());
731
        }
756
        }
732
    }
757
    }
733
    else if (o_Input->Mode() == TCP)
758
    else if ((o_Input->Mode() == TCP) && (t_Data[0] == '$'))
734
    {
759
    {
735
            parse_IP_Data(t_Data);
760
            parse_IP_Data(t_Data);
736
    }
761
    }
737
}
762
}
738
 
763
 
739
// Serververbindung beendet
764
// Serververbindung beendet
740
void dlg_Main::slot_Input_Disconnected(int Error)
765
void dlg_Main::slot_Input_Disconnected(int Error)
741
{
766
{
742
    cb_Server->setEnabled(true);
767
    cb_Server->setEnabled(true);
743
    le_Password->setEnabled(true);
768
    le_Password->setEnabled(true);
744
 
-
 
745
//    qDebug("Close");
769
 
746
    disconnect(o_Input, SIGNAL(sig_NewData(QString)), 0, 0);
-
 
747
    if (o_Input->Mode() == TCP)
-
 
748
    {
770
    disconnect(o_Input, SIGNAL(sig_NewData(QString)), 0, 0);
749
        disconnect(o_Input, SIGNAL(sig_Disconnected(int)), 0, 0);
771
    disconnect(o_Input, SIGNAL(sig_Disconnected(int)), 0, 0);
750
        disconnect(o_Input, SIGNAL(sig_Connected()), 0, 0);
772
    disconnect(o_Input, SIGNAL(sig_Connected()), 0, 0);
751
    }
773
 
752
    ac_Connect->setChecked(false);
774
    ac_Connect->setChecked(false);
753
    ac_Connect->setText(tr("Verbinden"));
775
    ac_Connect->setText(tr("Verbinden"));
754
    btn_Connect->setChecked(false);
776
    btn_Connect->setChecked(false);
755
 
777
 
756
    switch (Error)
778
    switch (Error)
757
    {
779
    {
758
        case REMOTECLOSED :
780
        case REMOTECLOSED :
759
        {
781
        {
760
//            lb_Status->setText(tr("Verbindung vom Server beendet."));
782
//            lb_Status->setText(tr("Verbindung vom Server beendet."));
761
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Verbindung wurde vom Server beendet."), QMessageBox::Ok);
783
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Verbindung wurde vom Server beendet."), QMessageBox::Ok);
762
        }
784
        }
763
        break;
785
        break;
764
        case REFUSED :
786
        case REFUSED :
765
        {
787
        {
766
//            lb_Status->setText(tr("Server nicht gefunden."));
788
//            lb_Status->setText(tr("Server nicht gefunden."));
767
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Kann nicht zum Server verbinden."), QMessageBox::Ok);
789
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Kann nicht zum Server verbinden."), QMessageBox::Ok);
768
        }
790
        }
769
        break;
791
        break;
770
        case 3 :
792
        case 3 :
771
        {
793
        {
772
//            lb_Status->setText(tr("Serververbindung getrennt. Logindaten falsch."));
794
//            lb_Status->setText(tr("Serververbindung getrennt. Logindaten falsch."));
773
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Loginname oder Password falsch."), QMessageBox::Ok);
795
            QMessageBox::warning(this, QA_NAME,tr("QMK-Datenserver: Loginname oder Password falsch."), QMessageBox::Ok);
774
        }
796
        }
775
        break;
797
        break;
776
        default :
798
        default :
777
        {
799
        {
778
//            lb_Status->setText(tr("Getrennt vom QMK-Datenserver."));
800
//            lb_Status->setText(tr("Getrennt vom QMK-Datenserver."));
779
        }
801
        }
780
        break;
802
        break;
781
    }
803
    }
782
 
804
 
783
}
805
}
784
 
806
 
785
// Serververbindung hergestellt
807
// Serververbindung hergestellt
786
void dlg_Main::slot_Input_Connected()
808
void dlg_Main::slot_Input_Connected()
787
{
809
{
788
    connect(o_Input, SIGNAL(sig_NewData(QString)), this, SLOT(slot_Input_Data(QString)));
810
    connect(o_Input, SIGNAL(sig_NewData(QString)), this, SLOT(slot_Input_Data(QString)));
789
 
-
 
790
    o_Input->send_Data(HandlerIP::make_Frame(0, 101, QA_NAME + " " + QA_VERSION));
811
 
791
    o_Input->send_Data(HandlerMK::make_Frame('v', 0, c_Data, 0).toLatin1().data(), DATA_VERSION);
812
    o_Input->send_Data(HandlerMK::make_Frame('v', 0, c_Data, 0).toLatin1().data(), DATA_VERSION);
792
    ac_Connect->setText(tr("Trennen"));
813
    ac_Connect->setText(tr("Trennen"));
793
}
814
}
794
 
815
 
795
///////////////////////////////////////////////////////////////////
816
///////////////////////////////////////////////////////////////////
796
// QMK-Maps                                                      //
817
// QMK-Maps                                                      //
797
///////////////////////////////////////////////////////////////////
818
///////////////////////////////////////////////////////////////////
798
 
819
 
799
// Zoom der Karte ändern
820
// Zoom der Karte ändern
800
void dlg_Main::slot_Zoom(int t_Zoom)
821
void dlg_Main::slot_Zoom(int t_Zoom)
801
{
822
{
802
    o_Map->setZoom(t_Zoom);
823
    o_Map->setZoom(t_Zoom);
803
}
824
}
804
 
825
 
805
// Karte wechseln
826
// Karte wechseln
806
void dlg_Main::slot_ChangeMap(int t_Set)
827
void dlg_Main::slot_ChangeMap(int t_Set)
807
{
828
{
808
    int zoom = o_Adapter->adaptedZoom();
829
    int zoom = o_Adapter->adaptedZoom();
809
    QPointF a = o_Map->currentCoordinate();
830
    QPointF a = o_Map->currentCoordinate();
810
 
831
 
811
    o_Map->setZoom(0);
832
    o_Map->setZoom(0);
812
 
833
 
813
    switch(t_Set)
834
    switch(t_Set)
814
    {
835
    {
815
        case 0 : // OpenStreetMap
836
        case 0 : // OpenStreetMap
816
        {
837
        {
817
            o_Adapter = new OSMMapAdapter();
838
            o_Adapter = new OSMMapAdapter();
818
        }
839
        }
819
        break;
840
        break;
820
        case 1 : // Yahoo Sat
841
        case 1 : // Yahoo Sat
821
        {
842
        {
822
            o_Adapter = new TileMapAdapter("tile.openaerialmap.org", "/tiles/1.0.0/openaerialmap-900913/%1/%2/%3.png", 256, 0, 17);
843
            o_Adapter = new TileMapAdapter("tile.openaerialmap.org", "/tiles/1.0.0/openaerialmap-900913/%1/%2/%3.png", 256, 0, 17);
823
        }
844
        }
824
        break;
845
        break;
825
        case 2 : // Google Maps
846
        case 2 : // Google Maps
826
        {
847
        {
827
            o_Adapter = new GoogleMapAdapter();
848
            o_Adapter = new GoogleMapAdapter();
828
        }
849
        }
829
        break;
850
        break;
830
        case 3 : // Google Sat
851
        case 3 : // Google Sat
831
        {
852
        {
832
            o_Adapter = new GoogleSatMapAdapter();
853
            o_Adapter = new GoogleSatMapAdapter();
833
        }
854
        }
834
        break;
855
        break;
835
        case 4 : // Yahoo Maps
856
        case 4 : // Yahoo Maps
836
        {
857
        {
837
            o_Adapter = new YahooMapAdapter();
858
            o_Adapter = new YahooMapAdapter();
838
        }
859
        }
839
        break;
860
        break;
840
        case 5 : // Yahoo Sat
861
        case 5 : // Yahoo Sat
841
        {
862
        {
842
            o_Adapter = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
863
            o_Adapter = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
843
        }
864
        }
844
        break;
865
        break;
845
    }
866
    }
846
 
867
 
847
    o_Layer->setMapAdapter(o_Adapter);
868
    o_Layer->setMapAdapter(o_Adapter);
848
    o_Click->setMapAdapter(o_Adapter);
869
    o_Click->setMapAdapter(o_Adapter);
849
    o_Info->setMapAdapter(o_Adapter);
870
    o_Info->setMapAdapter(o_Adapter);
850
    o_RouteWP->setMapAdapter(o_Adapter);
871
    o_RouteWP->setMapAdapter(o_Adapter);
851
    o_RouteFL->setMapAdapter(o_Adapter);
872
    o_RouteFL->setMapAdapter(o_Adapter);
852
 
873
 
853
    o_Map->updateRequestNew();
874
    o_Map->updateRequestNew();
854
    o_Map->setZoom(zoom);
875
    o_Map->setZoom(zoom);
855
}
876
}
856
 
877
 
857
// Click in die Karte
878
// Click in die Karte
858
void dlg_Main::slot_Click(const QMouseEvent* Event, const QPointF Coord)
879
void dlg_Main::slot_Click(const QMouseEvent* Event, const QPointF Coord)
859
{
880
{
860
    if ((Event->type() == QEvent::MouseButtonPress) && ((Event->button() == Qt::RightButton) || (Event->button() == Qt::MidButton)))
881
    if ((Event->type() == QEvent::MouseButtonPress) && ((Event->button() == Qt::RightButton) || (Event->button() == Qt::MidButton)))
861
    {
882
    {
862
        sl_Zoom->setValue(o_Adapter->adaptedZoom());
883
        sl_Zoom->setValue(o_Adapter->adaptedZoom());
863
    }
884
    }
864
 
885
 
865
    // Überwachen ob Karte verschoben wird
886
    // Überwachen ob Karte verschoben wird
866
    if ((Event->type() == QEvent::MouseButtonPress) && (Event->button() == Qt::LeftButton))
887
    if ((Event->type() == QEvent::MouseButtonPress) && (Event->button() == Qt::LeftButton))
867
    {
888
    {
868
        MapCenter = o_Map->currentCoordinate();
889
        MapCenter = o_Map->currentCoordinate();
869
    }
890
    }
870
 
891
 
871
    // Nur wenn nicht Verschoben dann einen Punkt setzen
892
    // Nur wenn nicht Verschoben dann einen Punkt setzen
872
    if ((Event->type() == QEvent::MouseButtonRelease) && (Event->button() == Qt::LeftButton))
893
    if ((Event->type() == QEvent::MouseButtonRelease) && (Event->button() == Qt::LeftButton))
873
    {
894
    {
874
        if (o_Map->currentCoordinate() == MapCenter)
895
        if (o_Map->currentCoordinate() == MapCenter)
875
        {
896
        {
876
            if (l_WayPoints.count() < 20)
897
            if (l_WayPoints.count() < 20)
877
            {
898
            {
878
                btn_WPAdd->setEnabled(true);
899
                btn_WPAdd->setEnabled(true);
879
            }
900
            }
880
 
901
 
881
            o_Click->removeGeometry(ClickPoint);
902
            o_Click->removeGeometry(ClickPoint);
882
 
903
 
883
            ClickPoint = new CirclePoint(Coord.x(), Coord.y(), 6, "P1", Point::Middle, Pen[2]);
904
            ClickPoint = new CirclePoint(Coord.x(), Coord.y(), 6, "P1", Point::Middle, Pen[2]);
884
 
905
 
885
 
906
 
886
            LastClick = new Point(Coord.x(), Coord.y());
907
            LastClick = new Point(Coord.x(), Coord.y());
887
 
908
 
888
            ClickPoint->setBaselevel(o_Adapter->adaptedZoom());
909
            ClickPoint->setBaselevel(o_Adapter->adaptedZoom());
889
            o_Click->addGeometry(ClickPoint);
910
            o_Click->addGeometry(ClickPoint);
890
 
911
 
891
//            o_Click->removeGeometry(Flag);
912
//            o_Click->removeGeometry(Flag);
892
//            Flag = new ImagePoint(Coord.x(), Coord.y(), ":/Flags/Global/Images/Flags/Target.png", "Start");
913
//            Flag = new ImagePoint(Coord.x(), Coord.y(), ":/Flags/Global/Images/Flags/Target.png", "Start");
893
//            Flag->setBaselevel(o_Adapter->adaptedZoom());
914
//            Flag->setBaselevel(o_Adapter->adaptedZoom());
894
//            o_Click->addGeometry(Flag);
915
//            o_Click->addGeometry(Flag);
895
 
916
 
896
 
917
 
897
            if (cb_Goto->isChecked())
918
            if (cb_Goto->isChecked())
898
            {
919
            {
899
                send_Target(LastClick);
920
                send_Target(LastClick);
900
            }
921
            }
901
        }
922
        }
902
    }
923
    }
903
 
924
 
904
    o_Map->updateRequestNew();
925
    o_Map->updateRequestNew();
905
//    qDebug(QString("%1").arg(Coord.x()).toLatin1().data());
926
//    qDebug(QString("%1").arg(Coord.x()).toLatin1().data());
906
//    qDebug(QString("%1").arg(Coord.y()).toLatin1().data());
927
//    qDebug(QString("%1").arg(Coord.y()).toLatin1().data());
907
}
928
}
908
 
929
 
909
// WayPoint zur Liste hinzufügen
930
// WayPoint zur Liste hinzufügen
910
void dlg_Main::slot_btn_WPAdd()
931
void dlg_Main::slot_btn_WPAdd()
911
{
932
{
912
    cb_ShowWPs->setChecked(true);
933
    cb_ShowWPs->setChecked(true);
913
 
934
 
914
    sWayPoint WayPoint;
935
    sWayPoint WayPoint;
915
 
936
 
916
    WayPoint.Longitude = LastClick->longitude();
937
    WayPoint.Longitude = LastClick->longitude();
917
    WayPoint.Latitude = LastClick->latitude();
938
    WayPoint.Latitude = LastClick->latitude();
918
    WayPoint.Time = sb_Time->value();
939
    WayPoint.Time = sb_Time->value();
919
 
940
 
920
    l_WayPoints.append(WayPoint);
941
    l_WayPoints.append(WayPoint);
921
 
942
 
922
    o_RouteWP->removeGeometry(l_RouteWP);
943
    o_RouteWP->removeGeometry(l_RouteWP);
923
 
944
 
924
    p_RouteWP.append(LastClick);
945
    p_RouteWP.append(LastClick);
925
    l_RouteWP = new LineString(p_RouteWP, "", Pen[3]);
946
    l_RouteWP = new LineString(p_RouteWP, "", Pen[3]);
926
 
947
 
927
    o_RouteWP->addGeometry(l_RouteWP);
948
    o_RouteWP->addGeometry(l_RouteWP);
928
    o_Map->updateRequestNew();
949
    o_Map->updateRequestNew();
929
 
950
 
930
    btn_WPFly->setEnabled(true);
951
    btn_WPFly->setEnabled(true);
931
 
952
 
932
    if (l_WayPoints.count() == 20)
953
    if (l_WayPoints.count() == 20)
933
    {
954
    {
934
        QMessageBox::warning(this, QA_NAME,trUtf8("Wegpunkt-Liste ist voll. Es können maximal 20 Wegpunkte benutzt werden."), QMessageBox::Ok);
955
        QMessageBox::warning(this, QA_NAME,trUtf8("Wegpunkt-Liste ist voll. Es können maximal 20 Wegpunkte benutzt werden."), QMessageBox::Ok);
935
        btn_WPAdd->setEnabled(false);
956
        btn_WPAdd->setEnabled(false);
936
    }
957
    }
937
}
958
}
938
 
959
 
939
// WayPoint-Liste übertragen
960
// WayPoint-Liste übertragen
940
void dlg_Main::slot_btn_WPFly()
961
void dlg_Main::slot_btn_WPFly()
941
{
962
{
942
    send_WayPoints(l_WayPoints, 0);
963
    send_WayPoints(l_WayPoints, 0);
943
}
964
}
944
 
965
 
945
// WayPpoint-Liste löschen
966
// WayPpoint-Liste löschen
946
void dlg_Main::slot_btn_WPDelete()
967
void dlg_Main::slot_btn_WPDelete()
947
{
968
{
948
    p_RouteWP.clear();
969
    p_RouteWP.clear();
949
    l_WayPoints.clear();
970
    l_WayPoints.clear();
950
    o_RouteWP->clearGeometries();
971
    o_RouteWP->clearGeometries();
951
    l_RouteWP = new LineString(p_RouteWP, "", Pen[0]);
972
    l_RouteWP = new LineString(p_RouteWP, "", Pen[0]);
952
//    o_RouteWP->addGeometry(l_RouteWP);
973
//    o_RouteWP->addGeometry(l_RouteWP);
953
//    o_RouteWP->removeGeometry(l_RouteWP);
974
//    o_RouteWP->removeGeometry(l_RouteWP);
954
 
975
 
955
    o_Map->updateRequestNew();
976
    o_Map->updateRequestNew();
956
 
977
 
957
    btn_WPFly->setEnabled(false);
978
    btn_WPFly->setEnabled(false);
958
    btn_WPAdd->setEnabled(true);
979
    btn_WPAdd->setEnabled(true);
959
}
980
}
960
 
981
 
961
// WayPoint-Liste laden
982
// WayPoint-Liste laden
962
void dlg_Main::slot_ac_LoadWayPoints()
983
void dlg_Main::slot_ac_LoadWayPoints()
963
{
984
{
964
    QString Filename = QFileDialog::getOpenFileName(this, "WayPoint-Route laden",  s_Dir.WPRoutes, "Mikrokopter WayPoints(*.mkw);;KML-Datei(*.kml);;Alle Dateien (*)");
985
    QString Filename = QFileDialog::getOpenFileName(this, "WayPoint-Route laden",  s_Dir.WPRoutes, "Mikrokopter WayPoints(*.mkw);;KML-Datei(*.kml);;Alle Dateien (*)");
965
 
986
 
966
    if (!Filename.isEmpty())
987
    if (!Filename.isEmpty())
967
    {
988
    {
968
        if (Filename.endsWith(".kml", Qt::CaseInsensitive))
989
        if (Filename.endsWith(".kml", Qt::CaseInsensitive))
969
        {
990
        {
970
            cb_ShowWPs->setChecked(true);
991
            cb_ShowWPs->setChecked(true);
971
            btn_WPFly->setEnabled(true);
992
            btn_WPFly->setEnabled(true);
972
 
993
 
973
            show_WayPoints(parse_WayPointKML(Filename));
994
            show_WayPoints(parse_WayPointKML(Filename));
974
        }
995
        }
975
        if (Filename.endsWith(".mkw", Qt::CaseInsensitive))
996
        if (Filename.endsWith(".mkw", Qt::CaseInsensitive))
976
        {
997
        {
977
            cb_ShowWPs->setChecked(true);
998
            cb_ShowWPs->setChecked(true);
978
            btn_WPFly->setEnabled(true);
999
            btn_WPFly->setEnabled(true);
979
 
1000
 
980
            show_WayPoints(parse_WayPointMKW(Filename));
1001
            show_WayPoints(parse_WayPointMKW(Filename));
981
        }
1002
        }
982
    }
1003
    }
983
}
1004
}
984
 
1005
 
985
// WayPoint-Liste speichern
1006
// WayPoint-Liste speichern
986
void dlg_Main::slot_ac_SaveRoute()
1007
void dlg_Main::slot_ac_SaveRoute()
987
{
1008
{
988
    QString Filename = QFileDialog::getSaveFileName(this, "WayPoint-Route speichern",  s_Dir.WPRoutes, "Mikrokopter WayPoints(*.mkw);;Alle Dateien (*)");
1009
    QString Filename = QFileDialog::getSaveFileName(this, "WayPoint-Route speichern",  s_Dir.WPRoutes, "Mikrokopter WayPoints(*.mkw);;Alle Dateien (*)");
989
 
1010
 
990
    if (!Filename.isEmpty())
1011
    if (!Filename.isEmpty())
991
    {
1012
    {
992
        if (!(Filename.endsWith(".mkw", Qt::CaseInsensitive)))
1013
        if (!(Filename.endsWith(".mkw", Qt::CaseInsensitive)))
993
        {
1014
        {
994
            Filename = Filename + QString(".mkw");
1015
            Filename = Filename + QString(".mkw");
995
        }
1016
        }
996
 
1017
 
997
        save_WayPointsMKW(Filename);
1018
        save_WayPointsMKW(Filename);
998
    }
1019
    }
999
}
1020
}
1000
 
1021
 
1001
// Route anzeigen / ausblenden
1022
// Route anzeigen / ausblenden
1002
void dlg_Main::slot_ShowWayPoints(bool Show)
1023
void dlg_Main::slot_ShowWayPoints(bool Show)
1003
{
1024
{
1004
    if (Show == true)
1025
    if (Show == true)
1005
    {
1026
    {
1006
//        qDebug("Error 1");
-
 
1007
        if (l_RouteWP->hasPoints())
1027
        if (l_RouteWP->hasPoints())
1008
        {
1028
        {
1009
//        qDebug("Error 2");
-
 
1010
            o_RouteWP->addGeometry(l_RouteWP);
1029
            o_RouteWP->addGeometry(l_RouteWP);
1011
//        qDebug("Error 3");
-
 
1012
            o_Map->updateRequestNew();
1030
            o_Map->updateRequestNew();
1013
//        qDebug("Error 4");
-
 
1014
        }
1031
        }
1015
    }
1032
    }
1016
    else
1033
    else
1017
    {
1034
    {
1018
        o_RouteWP->removeGeometry(l_RouteWP);
1035
        o_RouteWP->removeGeometry(l_RouteWP);
1019
        o_Map->updateRequestNew();
1036
        o_Map->updateRequestNew();
1020
    }
1037
    }
1021
}
1038
}
1022
 
1039
 
1023
// Bilddatei als Karteladen.
1040
// Bilddatei als Karteladen.
1024
void dlg_Main::slot_ac_LoadMapPic()
1041
void dlg_Main::slot_ac_LoadMapPic()
1025
{
1042
{
1026
    QString Filename = QFileDialog::getOpenFileName(this, "Bild als Karte",  s_Dir.MapPics, "Bilddatei(*.jpg *.png *.gif);;Alle Dateien (*)");
1043
    QString Filename = QFileDialog::getOpenFileName(this, "Bild als Karte",  s_Dir.MapPics, "Bilddatei(*.jpg *.png *.gif);;Alle Dateien (*)");
1027
 
1044
 
1028
    if (!Filename.isEmpty())
1045
    if (!Filename.isEmpty())
1029
    {
1046
    {
1030
        QFile *f_Points = new QFile(Filename + ".pos");
1047
        QFile *f_Points = new QFile(Filename + ".pos");
1031
 
1048
 
1032
        if (f_Points->exists())
1049
        if (f_Points->exists())
1033
        {
1050
        {
1034
            f_Points->open(QIODevice::ReadOnly | QIODevice::Text);
1051
            f_Points->open(QIODevice::ReadOnly | QIODevice::Text);
1035
 
1052
 
1036
            QString s_Points;
1053
            QString s_Points;
1037
 
1054
 
1038
            while (!f_Points->atEnd())
1055
            while (!f_Points->atEnd())
1039
            {
1056
            {
1040
                s_Points.append(f_Points->readLine());
1057
                s_Points.append(f_Points->readLine());
1041
            }
1058
            }
1042
 
1059
 
1043
            f_Points->close();
1060
            f_Points->close();
1044
 
1061
 
1045
            QStringList s_Pos = s_Points.split(",");
1062
            QStringList s_Pos = s_Points.split(",");
1046
 
1063
 
1047
            FixedImageOverlay* fip = new FixedImageOverlay(s_Pos[0].toDouble(), s_Pos[1].toDouble(), s_Pos[2].toDouble(), s_Pos[3].toDouble(), Filename);
1064
            FixedImageOverlay* fip = new FixedImageOverlay(s_Pos[0].toDouble(), s_Pos[1].toDouble(), s_Pos[2].toDouble(), s_Pos[3].toDouble(), Filename);
1048
 
1065
 
1049
            o_Layer->addGeometry(fip);
1066
            o_Layer->addGeometry(fip);
1050
            o_Map->setView(QPointF(((s_Pos[0].toDouble() + s_Pos[2].toDouble()) / 2),((s_Pos[1].toDouble() + s_Pos[3].toDouble()) / 2)));
1067
            o_Map->setView(QPointF(((s_Pos[0].toDouble() + s_Pos[2].toDouble()) / 2),((s_Pos[1].toDouble() + s_Pos[3].toDouble()) / 2)));
1051
 
1068
 
1052
            o_Map->updateRequestNew();
1069
            o_Map->updateRequestNew();
1053
        }
1070
        }
1054
        else
1071
        else
1055
        {
1072
        {
1056
            dlg_MapPos *f_MapPos = new dlg_MapPos(this);
1073
            dlg_MapPos *f_MapPos = new dlg_MapPos(this);
1057
 
1074
 
1058
            if (f_MapPos->exec()==QDialog::Accepted)
1075
            if (f_MapPos->exec()==QDialog::Accepted)
1059
            {
1076
            {
1060
                QString Data = f_MapPos->get_Data();
1077
                QString Data = f_MapPos->get_Data();
1061
 
1078
 
1062
                f_Points->open(QIODevice::ReadWrite | QIODevice::Text);
1079
                f_Points->open(QIODevice::ReadWrite | QIODevice::Text);
1063
 
1080
 
1064
                QTextStream out(f_Points);
1081
                QTextStream out(f_Points);
1065
 
1082
 
1066
                out.setRealNumberPrecision(9);
1083
                out.setRealNumberPrecision(9);
1067
 
1084
 
1068
                out << Data << "\n";
1085
                out << Data << "\n";
1069
 
1086
 
1070
                f_Points->close();
1087
                f_Points->close();
1071
 
1088
 
1072
                QStringList s_Pos = Data.split(",");
1089
                QStringList s_Pos = Data.split(",");
1073
 
1090
 
1074
                FixedImageOverlay* fip = new FixedImageOverlay(s_Pos[0].toDouble(), s_Pos[1].toDouble(), s_Pos[2].toDouble(), s_Pos[3].toDouble(), Filename);
1091
                FixedImageOverlay* fip = new FixedImageOverlay(s_Pos[0].toDouble(), s_Pos[1].toDouble(), s_Pos[2].toDouble(), s_Pos[3].toDouble(), Filename);
1075
 
1092
 
1076
                o_Layer->addGeometry(fip);
1093
                o_Layer->addGeometry(fip);
1077
                o_Map->updateRequestNew();
1094
                o_Map->updateRequestNew();
1078
            }
1095
            }
1079
 
1096
 
1080
        }
1097
        }
1081
    }
1098
    }
1082
}
1099
}
1083
 
1100
 
1084
// Flug als KML aufzeichnen
1101
// Flug als KML aufzeichnen
1085
void dlg_Main::slot_ac_Record()
1102
void dlg_Main::slot_ac_Record()
1086
{
1103
{
1087
    if (ac_Record->isChecked())
1104
    if (ac_Record->isChecked())
1088
    {
1105
    {
1089
        QString f_Name = s_Dir.Flights + "/" + QDate::currentDate().toString(("yyyy-MM-dd")) + "_" + QTime::currentTime().toString("hh-mm");
1106
        QString f_Name = s_Dir.Flights + "/" + QDate::currentDate().toString(("yyyy-MM-dd")) + "_" + QTime::currentTime().toString("hh-mm");
1090
 
1107
 
1091
        ac_Record->setText(tr("Stoppen"));
1108
        ac_Record->setText(tr("Stoppen"));
1092
 
1109
 
1093
        o_Record = new QFile(f_Name + ".kml");
1110
        o_Record = new QFile(f_Name + ".kml");
1094
        o_Record->open(QIODevice::Append | QIODevice::Text);
1111
        o_Record->open(QIODevice::Append | QIODevice::Text);
1095
 
1112
 
1096
        QTextStream Out(o_Record);
1113
        QTextStream Out(o_Record);
1097
        Out << HandlerKML::get_Header(tr("Mikrokopter Flugaufzeichnung")) << "\n";
1114
        Out << HandlerKML::get_Header(tr("Mikrokopter Flugaufzeichnung")) << "\n";
1098
 
1115
 
1099
    }
1116
    }
1100
    else
1117
    else
1101
    {
1118
    {
1102
        QTextStream Out(o_Record);
1119
        QTextStream Out(o_Record);
1103
        Out << HandlerKML::get_Footer() << "\n";
1120
        Out << HandlerKML::get_Footer() << "\n";
1104
        o_Record->close();
1121
        o_Record->close();
1105
        ac_Record->setText(tr("Aufzeichnen"));
1122
        ac_Record->setText(tr("Aufzeichnen"));
1106
    }
1123
    }
1107
}
1124
}
1108
 
1125
 
1109
// WayPpoint-Liste löschen
1126
// WayPpoint-Liste löschen
1110
void dlg_Main::slot_ac_RouteDelete()
1127
void dlg_Main::slot_ac_RouteDelete()
1111
{
1128
{
1112
    p_RouteFL.clear();
1129
    p_RouteFL.clear();
1113
    l_Track.clear();
1130
    l_Track.clear();
1114
    o_RouteFL->clearGeometries();
1131
    o_RouteFL->clearGeometries();
1115
    l_RouteFL = new LineString(p_RouteFL, "", Pen[0]);
1132
    l_RouteFL = new LineString(p_RouteFL, "", Pen[0]);
1116
//    o_RouteFL->removeGeometry(l_RouteFL);
1133
//    o_RouteFL->removeGeometry(l_RouteFL);
1117
 
1134
 
1118
    o_Map->updateRequestNew();
1135
    o_Map->updateRequestNew();
1119
}
1136
}
1120
 
1137
 
1121
// Programm Ende
1138
// Programm Ende
1122
dlg_Main::~dlg_Main()
1139
dlg_Main::~dlg_Main()
1123
{
1140
{
1124
    o_Settings->GUI.isMax       = isMaximized();
1141
    o_Settings->GUI.isMax       = isMaximized();
1125
    o_Settings->GUI.Size        = size();
1142
    o_Settings->GUI.Size        = size();
1126
    o_Settings->GUI.Point       = pos();
1143
    o_Settings->GUI.Point       = pos();
1127
    o_Settings->GUI.Toolbar     = ac_Toolbar->isChecked();
1144
    o_Settings->GUI.Toolbar     = ac_Toolbar->isChecked();
1128
 
1145
 
1129
    o_Settings->DATA.Intervall = sb_Intervall->value();
1146
    o_Settings->DATA.Intervall = sb_Intervall->value();
1130
 
1147
 
1131
    o_Settings->SERVER.Password = le_Password->text();
1148
    o_Settings->SERVER.Password = le_Password->text();
1132
    o_Settings->SERVER.IP_MAX  = cb_Server->count();
1149
    o_Settings->SERVER.IP_MAX  = cb_Server->count();
1133
    o_Settings->SERVER.IP_ID   = cb_Server->currentIndex();
1150
    o_Settings->SERVER.IP_ID   = cb_Server->currentIndex();
1134
 
1151
 
1135
    for (int z = 0; z < cb_Server->count(); z++)
1152
    for (int z = 0; z < cb_Server->count(); z++)
1136
    {
1153
    {
1137
        if (z < 10)
1154
        if (z < 10)
1138
        {
1155
        {
1139
            o_Settings->SERVER.IP[z] = cb_Server->itemText(z);
1156
            o_Settings->SERVER.IP[z] = cb_Server->itemText(z);
1140
        }
1157
        }
1141
    }
1158
    }
1142
 
1159
 
1143
    o_Settings->CONFIG.cb_CenterPos = cb_CenterPos->isChecked();
1160
    o_Settings->CONFIG.cb_CenterPos = cb_CenterPos->isChecked();
1144
    o_Settings->CONFIG.cb_ShowRoute = cb_ShowRoute->isChecked();
1161
    o_Settings->CONFIG.cb_ShowRoute = cb_ShowRoute->isChecked();
1145
    o_Settings->CONFIG.cb_ShowWPs   = cb_ShowWPs->isChecked();
1162
    o_Settings->CONFIG.cb_ShowWPs   = cb_ShowWPs->isChecked();
1146
    o_Settings->CONFIG.cb_Goto      = cb_Goto->isChecked();
1163
    o_Settings->CONFIG.cb_Goto      = cb_Goto->isChecked();
1147
 
1164
 
1148
    o_Settings->NAVI.StayTime = sb_Time->value();
1165
    o_Settings->NAVI.StayTime = sb_Time->value();
1149
 
1166
 
1150
    o_Settings->write_Settings();
1167
    o_Settings->write_Settings();
1151
 
1168
 
1152
//    qDebug("Ende.");
1169
//    qDebug("Ende.");
1153
}
1170
}
1154
 
1171