Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
38275d4f
Commit
38275d4f
authored
Jan 30, 2012
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Next step towards the new design of "Editable Waypoint" widget. Back-up only. Do not use!
parent
4044530f
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
632 additions
and
824 deletions
+632
-824
qgroundcontrol.pro
qgroundcontrol.pro
+6
-3
WaypointEditableView.cc
src/ui/WaypointEditableView.cc
+128
-415
WaypointEditableView.h
src/ui/WaypointEditableView.h
+25
-9
WaypointEditableView.ui
src/ui/WaypointEditableView.ui
+1
-392
QGCMissionNavWaypoint.cc
src/ui/mission/QGCMissionNavWaypoint.cc
+68
-0
QGCMissionNavWaypoint.h
src/ui/mission/QGCMissionNavWaypoint.h
+32
-0
QGCMissionNavWaypoint.ui
src/ui/mission/QGCMissionNavWaypoint.ui
+343
-0
QGCMissionOther.cc
src/ui/mission/QGCMissionOther.cc
+24
-2
QGCMissionOther.h
src/ui/mission/QGCMissionOther.h
+4
-2
QGCMissionOther.ui
src/ui/mission/QGCMissionOther.ui
+1
-1
No files found.
qgroundcontrol.pro
View file @
38275d4f
...
...
@@ -240,7 +240,8 @@ FORMS += src/ui/MainWindow.ui \
src
/
ui
/
firmwareupdate
/
QGCFirmwareUpdateWidget
.
ui
\
src
/
ui
/
QGCPluginHost
.
ui
\
src
/
ui
/
firmwareupdate
/
QGCPX4FirmwareUpdate
.
ui
\
src
/
ui
/
mission
/
QGCMissionOther
.
ui
src
/
ui
/
mission
/
QGCMissionOther
.
ui
\
src
/
ui
/
mission
/
QGCMissionNavWaypoint
.
ui
INCLUDEPATH
+=
src
\
src
/
ui
\
src
/
ui
/
linechart
\
...
...
@@ -364,7 +365,8 @@ HEADERS += src/MG.h \
src
/
ui
/
firmwareupdate
/
QGCFirmwareUpdateWidget
.
h
\
src
/
ui
/
QGCPluginHost
.
h
\
src
/
ui
/
firmwareupdate
/
QGCPX4FirmwareUpdate
.
h
\
src
/
ui
/
mission
/
QGCMissionOther
.
h
src
/
ui
/
mission
/
QGCMissionOther
.
h
\
src
/
ui
/
mission
/
QGCMissionNavWaypoint
.
h
#
Google
Earth
is
only
supported
on
Mac
OS
and
Windows
with
Visual
Studio
Compiler
macx
|
macx
-
g
++
|
macx
-
g
++
42
|
win32
-
msvc2008
|
win32
-
msvc2010
::
HEADERS
+=
src
/
ui
/
map3D
/
QGCGoogleEarthView
.
h
...
...
@@ -497,7 +499,8 @@ SOURCES += src/main.cc \
src
/
ui
/
firmwareupdate
/
QGCFirmwareUpdateWidget
.
cc
\
src
/
ui
/
QGCPluginHost
.
cc
\
src
/
ui
/
firmwareupdate
/
QGCPX4FirmwareUpdate
.
cc
\
src
/
ui
/
mission
/
QGCMissionOther
.
cc
src
/
ui
/
mission
/
QGCMissionOther
.
cc
\
src
/
ui
/
mission
/
QGCMissionNavWaypoint
.
cc
#
Enable
Google
Earth
only
on
Mac
OS
and
Windows
with
Visual
Studio
compiler
macx
|
macx
-
g
++
|
macx
-
g
++
42
|
win32
-
msvc2008
|
win32
-
msvc2010
::
SOURCES
+=
src
/
ui
/
map3D
/
QGCGoogleEarthView
.
cc
...
...
src/ui/WaypointEditableView.cc
View file @
38275d4f
This diff is collapsed.
Click to expand it.
src/ui/WaypointEditableView.h
View file @
38275d4f
...
...
@@ -38,9 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <iostream>
enum
QGC_WAYPOINTEDITABLEVIEW_MODE
{
QGC_WAYPOINTEDITABLEVIEW_MODE_NAV
,
QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION
,
QGC_WAYPOINTEDITABLEVIEW_MODE_DO
,
QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT
,
QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING
};
...
...
@@ -50,6 +48,7 @@ class WaypointEditableView;
}
//class Ui_QGCCustomWaypointAction;
//class Ui_QGCMissionDoWidget;
class
QGCMissionNavWaypoint
;
class
QGCMissionDoWidget
;
class
QGCMissionConditionWidget
;
class
QGCMissionOther
;
...
...
@@ -70,22 +69,30 @@ public slots:
void
remove
();
/** @brief Waypoint matching this widget has been deleted */
void
deleted
(
QObject
*
waypoint
);
void
changedAutoContinue
(
int
);
void
updateFrameView
(
int
frame
);
void
changedAutoContinue
(
int
);
void
changedFrame
(
int
state
);
void
updateActionView
(
int
action
);
void
changedAction
(
int
state
);
void
changedCurrent
(
int
);
void
updateValues
(
void
);
void
changedAction
(
int
state
);
//change commandID, including the view
void
changedCommand
(
int
mav_cmd_id
);
//only update WP->command, but do not change the view. Should only be used for "other" waypoint-type.
void
changedParam1
(
double
value
);
void
changedParam2
(
double
value
);
void
changedParam3
(
double
value
);
void
changedParam4
(
double
value
);
void
changedParam5
(
double
value
);
void
changedParam6
(
double
value
);
void
changedParam7
(
double
value
);
protected
slots
:
void
changeViewMode
(
QGC_WAYPOINTEDITABLEVIEW_MODE
mode
);
protected:
virtual
void
changeEvent
(
QEvent
*
e
);
Waypoint
*
wp
;
// Special widgets extendending the
// waypoint view to mission capabilities
QGCMissionNavWaypoint
*
MissionNavWaypointWidget
;
QGCMissionDoWidget
*
MissionDoJumpWidget
;
QGCMissionConditionWidget
*
MissionConditionDelayWidget
;
QGCMissionOther
*
MissionOtherWidget
;
...
...
@@ -97,10 +104,19 @@ private:
signals:
void
moveUpWaypoint
(
Waypoint
*
);
void
moveDownWaypoint
(
Waypoint
*
);
void
removeWaypoint
(
Waypoint
*
);
//void currentWaypointChanged(quint16); //unused
void
removeWaypoint
(
Waypoint
*
);
void
changeCurrentWaypoint
(
quint16
);
void
setYaw
(
double
);
void
commandBroadcast
(
int
mav_cmd_id
);
void
frameBroadcast
(
MAV_FRAME
frame
);
void
param1Broadcast
(
double
value
);
void
param2Broadcast
(
double
value
);
void
param3Broadcast
(
double
value
);
void
param4Broadcast
(
double
value
);
void
param5Broadcast
(
double
value
);
void
param6Broadcast
(
double
value
);
void
param7Broadcast
(
double
value
);
};
#endif // WAYPOINTEDITABLEVIEW_H
src/ui/WaypointEditableView.ui
View file @
38275d4f
This diff is collapsed.
Click to expand it.
src/ui/mission/QGCMissionNavWaypoint.cc
0 → 100644
View file @
38275d4f
#include "QGCMissionNavWaypoint.h"
#include "ui_QGCMissionNavWaypoint.h"
#include "WaypointEditableView.h"
QGCMissionNavWaypoint
::
QGCMissionNavWaypoint
(
WaypointEditableView
*
WEV
)
:
QWidget
(
WEV
),
ui
(
new
Ui
::
QGCMissionNavWaypoint
)
{
ui
->
setupUi
(
this
);
this
->
WEV
=
WEV
;
//Using UI to change WP:
connect
(
this
->
ui
->
holdTimeSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam1
(
double
)));
connect
(
this
->
ui
->
acceptanceSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam2
(
double
)));
//connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double)));
connect
(
this
->
ui
->
yawSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam4
(
double
)));
connect
(
this
->
ui
->
posNSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam5
(
double
)));
//NED
connect
(
this
->
ui
->
posESpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam6
(
double
)));
connect
(
this
->
ui
->
posDSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam7
(
double
)));
connect
(
this
->
ui
->
latSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam5
(
double
)));
//Global
connect
(
this
->
ui
->
lonSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam6
(
double
)));
connect
(
this
->
ui
->
altSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam7
(
double
)));
//Reading WP to update UI:
connect
(
WEV
,
SIGNAL
(
frameBroadcast
(
MAV_FRAME
)),
this
,
SLOT
(
updateFrame
(
MAV_FRAME
)));
connect
(
WEV
,
SIGNAL
(
param1Broadcast
(
double
)),
this
->
ui
->
holdTimeSpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param2Broadcast
(
double
)),
this
->
ui
->
acceptanceSpinBox
,
SLOT
(
setValue
(
double
)));
//connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double)));
connect
(
WEV
,
SIGNAL
(
param4Broadcast
(
double
)),
this
->
ui
->
yawSpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param5Broadcast
(
double
)),
this
->
ui
->
posNSpinBox
,
SLOT
(
setValue
(
double
)));
//NED
connect
(
WEV
,
SIGNAL
(
param6Broadcast
(
double
)),
this
->
ui
->
posESpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param7Broadcast
(
double
)),
this
->
ui
->
posDSpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param5Broadcast
(
double
)),
this
->
ui
->
latSpinBox
,
SLOT
(
setValue
(
double
)));
//Global
connect
(
WEV
,
SIGNAL
(
param6Broadcast
(
double
)),
this
->
ui
->
lonSpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param7Broadcast
(
double
)),
this
->
ui
->
altSpinBox
,
SLOT
(
setValue
(
double
)));
}
void
QGCMissionNavWaypoint
::
updateFrame
(
MAV_FRAME
frame
)
{
switch
(
frame
)
{
case
MAV_FRAME_LOCAL_ENU
:
case
MAV_FRAME_LOCAL_NED
:
this
->
ui
->
posNSpinBox
->
show
();
this
->
ui
->
posESpinBox
->
show
();
this
->
ui
->
posDSpinBox
->
show
();
this
->
ui
->
latSpinBox
->
hide
();
this
->
ui
->
lonSpinBox
->
hide
();
this
->
ui
->
altSpinBox
->
hide
();
break
;
case
MAV_FRAME_GLOBAL
:
case
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
this
->
ui
->
posNSpinBox
->
hide
();
this
->
ui
->
posESpinBox
->
hide
();
this
->
ui
->
posDSpinBox
->
hide
();
this
->
ui
->
latSpinBox
->
show
();
this
->
ui
->
lonSpinBox
->
show
();
this
->
ui
->
altSpinBox
->
show
();
break
;
default:
break
;
}
}
QGCMissionNavWaypoint
::~
QGCMissionNavWaypoint
()
{
delete
ui
;
}
src/ui/mission/QGCMissionNavWaypoint.h
0 → 100644
View file @
38275d4f
#ifndef QGCMISSIONNAVWAYPOINT_H
#define QGCMISSIONNAVWAYPOINT_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace
Ui
{
class
QGCMissionNavWaypoint
;
}
class
QGCMissionNavWaypoint
:
public
QWidget
{
Q_OBJECT
public:
explicit
QGCMissionNavWaypoint
(
WaypointEditableView
*
WEV
);
~
QGCMissionNavWaypoint
();
public
slots
:
void
updateFrame
(
MAV_FRAME
);
protected:
WaypointEditableView
*
WEV
;
private:
Ui
::
QGCMissionNavWaypoint
*
ui
;
};
#endif // QGCMISSIONNAVWAYPOINT_H
src/ui/mission/QGCMissionNavWaypoint.ui
0 → 100644
View file @
38275d4f
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
QGCMissionNavWaypoint
</class>
<widget
class=
"QWidget"
name=
"QGCMissionNavWaypoint"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
2208
</width>
<height>
37
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
200
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
/>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<property
name=
"spacing"
>
<number>
5
</number>
</property>
<property
name=
"margin"
>
<number>
0
</number>
</property>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"posNSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::WheelFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position X coordinate
</string>
</property>
<property
name=
"statusTip"
>
<string>
Position X corrdinate
</string>
</property>
<property
name=
"wrapping"
>
<bool>
false
</bool>
</property>
<property
name=
"frame"
>
<bool>
true
</bool>
</property>
<property
name=
"accelerated"
>
<bool>
true
</bool>
</property>
<property
name=
"prefix"
>
<string>
N
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"minimum"
>
<double>
-10000.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
10000.000000000000000
</double>
</property>
<property
name=
"singleStep"
>
<double>
0.050000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"posESpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::WheelFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position Y/Longitude coordinate
</string>
</property>
<property
name=
"statusTip"
>
<string>
Position Y/Longitude coordinate
</string>
</property>
<property
name=
"prefix"
>
<string>
E
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"minimum"
>
<double>
-10000.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
10000.000000000000000
</double>
</property>
<property
name=
"singleStep"
>
<double>
0.050000000000000
</double>
</property>
<property
name=
"value"
>
<double>
0.000000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"posDSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::WheelFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Position Z coordinate (local frame, negative)
</string>
</property>
<property
name=
"statusTip"
>
<string/>
</property>
<property
name=
"prefix"
>
<string>
D
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"minimum"
>
<double>
-10000.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
10000.000000000000000
</double>
</property>
<property
name=
"singleStep"
>
<double>
0.050000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"latSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::WheelFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Latitude in degrees
</string>
</property>
<property
name=
"statusTip"
>
<string>
Latitude in degrees
</string>
</property>
<property
name=
"prefix"
>
<string>
lat
</string>
</property>
<property
name=
"suffix"
>
<string>
°
</string>
</property>
<property
name=
"decimals"
>
<number>
7
</number>
</property>
<property
name=
"minimum"
>
<double>
-90.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
90.000000000000000
</double>
</property>
<property
name=
"singleStep"
>
<double>
0.000010000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"lonSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::WheelFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Longitude in degrees
</string>
</property>
<property
name=
"statusTip"
>
<string>
Longitude in degrees
</string>
</property>
<property
name=
"prefix"
>
<string>
lon
</string>
</property>
<property
name=
"suffix"
>
<string>
°
</string>
</property>
<property
name=
"decimals"
>
<number>
7
</number>
</property>
<property
name=
"minimum"
>
<double>
-180.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
180.000000000000000
</double>
</property>
<property
name=
"singleStep"
>
<double>
0.000010000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"altSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"toolTip"
>
<string>
Altitude in meters
</string>
</property>
<property
name=
"statusTip"
>
<string>
Altitude in meters
</string>
</property>
<property
name=
"prefix"
>
<string>
alt
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"decimals"
>
<number>
2
</number>
</property>
<property
name=
"minimum"
>
<double>
-100000.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
100000.000000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"yawSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"focusPolicy"
>
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Rotary wing only: Desired yaw angle at waypoint
</string>
</property>
<property
name=
"statusTip"
>
<string>
Rotary wing only: Desired yaw angle at waypoint
</string>
</property>
<property
name=
"wrapping"
>
<bool>
true
</bool>
</property>
<property
name=
"prefix"
>
<string/>
</property>
<property
name=
"suffix"
>
<string>
°
</string>
</property>
<property
name=
"decimals"
>
<number>
0
</number>
</property>
<property
name=
"minimum"
>
<double>
-180.000000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
180.000000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"acceptanceSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"toolTip"
>
<string>
Uncertainty radius in meters
where to accept this waypoint as reached
</string>
</property>
<property
name=
"statusTip"
>
<string>
Uncertainty radius in meters where to accept this waypoint as reached
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"value"
>
<double>
0.200000000000000
</double>
</property>
</widget>
</item>
<item>
<widget
class=
"QDoubleSpinBox"
name=
"holdTimeSpinBox"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Fixed"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"toolTip"
>
<string>
Time to stay/loiter at this position before advancing
</string>
</property>
<property
name=
"statusTip"
>
<string>
Time to stay/loiter at this position before advancing
</string>
</property>
<property
name=
"suffix"
>
<string>
s
</string>
</property>
<property
name=
"maximum"
>
<double>
9999.989999999999782
</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
src/ui/mission/QGCMissionOther.cc
View file @
38275d4f
#include "QGCMissionOther.h"
#include "ui_QGCMissionOther.h"
#include "WaypointEditableView.h"
QGCMissionOther
::
QGCMissionOther
(
QWidget
*
parent
)
:
QWidget
(
parent
),
QGCMissionOther
::
QGCMissionOther
(
WaypointEditableView
*
WEV
)
:
QWidget
(
WEV
),
ui
(
new
Ui
::
QGCMissionOther
)
{
ui
->
setupUi
(
this
);
this
->
WEV
=
WEV
;
//Using UI to change WP:
connect
(
this
->
ui
->
commandSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
WEV
,
SLOT
(
changedCommand
(
int
)));
connect
(
this
->
ui
->
param1SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam1
(
double
)));
connect
(
this
->
ui
->
param2SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam2
(
double
)));
connect
(
this
->
ui
->
param3SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam3
(
double
)));
connect
(
this
->
ui
->
param4SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam4
(
double
)));
connect
(
this
->
ui
->
param5SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam5
(
double
)));
connect
(
this
->
ui
->
param6SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam6
(
double
)));
connect
(
this
->
ui
->
param7SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
WEV
,
SLOT
(
changedParam7
(
double
)));
//Reading WP to update UI:
connect
(
WEV
,
SIGNAL
(
commandBroadcast
(
int
)),
this
->
ui
->
commandSpinBox
,
SLOT
(
setValue
(
int
)));
connect
(
WEV
,
SIGNAL
(
param1Broadcast
(
double
)),
this
->
ui
->
param1SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param2Broadcast
(
double
)),
this
->
ui
->
param2SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param3Broadcast
(
double
)),
this
->
ui
->
param3SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param4Broadcast
(
double
)),
this
->
ui
->
param4SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param5Broadcast
(
double
)),
this
->
ui
->
param5SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param6Broadcast
(
double
)),
this
->
ui
->
param6SpinBox
,
SLOT
(
setValue
(
double
)));
connect
(
WEV
,
SIGNAL
(
param7Broadcast
(
double
)),
this
->
ui
->
param7SpinBox
,
SLOT
(
setValue
(
double
)));
}
QGCMissionOther
::~
QGCMissionOther
()
...
...
src/ui/mission/QGCMissionOther.h
View file @
38275d4f
...
...
@@ -2,6 +2,7 @@
#define QGCMISSIONOTHER_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace
Ui
{
class
QGCMissionOther
;
...
...
@@ -12,13 +13,14 @@ class QGCMissionOther : public QWidget
Q_OBJECT
public:
explicit
QGCMissionOther
(
QWidget
*
parent
=
0
);
explicit
QGCMissionOther
(
WaypointEditableView
*
WEV
);
~
QGCMissionOther
();
Ui
::
QGCMissionOther
*
ui
;
protected:
WaypointEditableView
*
WEV
;
private:
};
#endif // QGCMISSIONOTHER_H
src/ui/mission/QGCMissionOther.ui
View file @
38275d4f
...
...
@@ -13,7 +13,7 @@
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"10,
0,10,10,10,10,0,
0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"10,
10,10,10,10,10,10,1
0"
>
<property
name=
"spacing"
>
<number>
5
</number>
</property>
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment