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
a347a659
Commit
a347a659
authored
Feb 14, 2012
by
LM
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Formatting, fixing audio alarms
parent
24560f76
Changes
9
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
685 additions
and
651 deletions
+685
-651
.gitignore
.gitignore
+0
-1
alert.wav
files/audio/alert.wav
+0
-0
qgroundcontrol.pri
qgroundcontrol.pri
+4
-11
GAudioOutput.cc
src/GAudioOutput.cc
+34
-17
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+47
-37
UAS.cc
src/uas/UAS.cc
+563
-567
UAS.h
src/uas/UAS.h
+2
-1
HSIDisplay.cc
src/ui/HSIDisplay.cc
+34
-17
HSIDisplay.h
src/ui/HSIDisplay.h
+1
-0
No files found.
.gitignore
View file @
a347a659
...
...
@@ -22,7 +22,6 @@ debug
release
qgroundcontrol
mavlinkgen-build-desktop
*.wav
qgroundcontrol.xcodeproj/**
doc/html
doc/doxy.log
...
...
audio/alert.wav
→
files/
audio/alert.wav
View file @
a347a659
File moved
qgroundcontrol.pri
View file @
a347a659
...
...
@@ -81,8 +81,6 @@ macx|macx-g++42|macx-g++: {
ICON = $$BASEDIR/images/icons/macx.icns
# Copy audio files if needed
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy contributed files
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy google earth starter file
...
...
@@ -274,7 +272,6 @@ message("Compiling for linux 32")
}
# Validated copy commands
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR
...
...
@@ -367,7 +364,6 @@ linux-g++-64 {
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug
}
DESTDIR = $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/debug
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/debug
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/debug/images
...
...
@@ -378,7 +374,6 @@ linux-g++-64 {
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release
}
DESTDIR = $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/release
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$TARGETDIR/release
QMAKE_POST_LINK += && mkdir -p $$TARGETDIR/release/images
...
...
@@ -455,7 +450,6 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\debug\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\debug\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\debug\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
...
...
@@ -476,7 +470,6 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/release) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\release\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\release\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\release\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\release\\earth.html" $$escape_expand(\\n))
...
...
@@ -543,13 +536,13 @@ win32-g++ {
message("Using cp to copy image and audio files to executable")
debug {
QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll
QMAKE_POST_LINK += && cp -r $$BASEDIR/
audio $$TARGETDIR/debug/audio
QMAKE_POST_LINK += && cp -r $$BASEDIR/
files $$TARGETDIR/debug/files
QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models
}
release {
QMAKE_POST_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll
QMAKE_POST_LINK += && cp -r $$BASEDIR/
audio $$TARGETDIR/release/audio
QMAKE_POST_LINK += && cp -r $$BASEDIR/
files $$TARGETDIR/release/files
QMAKE_POST_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models
}
...
...
@@ -561,14 +554,14 @@ win32-g++ {
exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\"
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\
audio\" \"$$TARGETDIR_WIN\\debug\\audio
\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\
files\" \"$$TARGETDIR_WIN\\debug\\files
\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\debug\\models\\\" /S /E /Y
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\debug\\earth.html\"
}
exists($$TARGETDIR/release) {
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\release\\SDL.dll\"
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\
audio\" \"$$TARGETDIR_WIN\\release\\audio
\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\
files\" \"$$TARGETDIR_WIN\\release\\files
\\\" /S /E /Y
QMAKE_POST_LINK += && xcopy \"$$BASEDIR_WIN\\models\" \"$$TARGETDIR_WIN\\release\\models\\\" /S /E /Y
QMAKE_POST_LINK += && copy /Y \"$$BASEDIR_WIN\\images\\earth.html\" \"$$TARGETDIR_WIN\\release\\earth.html\"
}
...
...
src/GAudioOutput.cc
View file @
a347a659
...
...
@@ -77,7 +77,8 @@ extern "C" {
GAudioOutput
*
GAudioOutput
::
instance
()
{
static
GAudioOutput
*
_instance
=
0
;
if
(
_instance
==
0
)
{
if
(
_instance
==
0
)
{
_instance
=
new
GAudioOutput
();
// Set the application as parent to ensure that this object
// will be destroyed when the main application exits
...
...
@@ -106,12 +107,16 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
#if _MSC_VER2
ISpVoice
*
pVoice
=
NULL
;
if
(
FAILED
(
::
CoInitialize
(
NULL
)))
{
if
(
FAILED
(
::
CoInitialize
(
NULL
)))
{
qDebug
(
"Creating COM object for audio output failed!"
);
}
else
{
}
else
{
HRESULT
hr
=
CoCreateInstance
(
CLSID_SpVoice
,
NULL
,
CLSCTX_ALL
,
IID_ISpVoice
,
(
void
**
)
&
pVoice
;);
if
(
SUCCEEDED
(
hr
)
)
{
if
(
SUCCEEDED
(
hr
)
)
{
hr
=
pVoice
->
Speak
(
L"Hello world"
,
0
,
NULL
);
pVoice
->
Release
();
pVoice
=
NULL
;
...
...
@@ -146,7 +151,8 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
void
GAudioOutput
::
mute
(
bool
mute
)
{
if
(
mute
!=
muted
)
{
if
(
mute
!=
muted
)
{
this
->
muted
=
mute
;
QSettings
settings
;
settings
.
setValue
(
QGC_GAUDIOOUTPUT_KEY
+
"muted"
,
this
->
muted
);
...
...
@@ -162,11 +168,13 @@ bool GAudioOutput::isMuted()
bool
GAudioOutput
::
say
(
QString
text
,
int
severity
)
{
if
(
!
muted
)
{
if
(
!
muted
)
{
// TODO Add severity filter
Q_UNUSED
(
severity
);
bool
res
=
false
;
if
(
!
emergency
)
{
if
(
!
emergency
)
{
// Speech synthesis is only supported with MSVC compiler
#ifdef _MSC_VER2
...
...
@@ -202,7 +210,9 @@ bool GAudioOutput::say(QString text, int severity)
#endif
}
return
res
;
}
else
{
}
else
{
return
false
;
}
}
...
...
@@ -212,22 +222,26 @@ bool GAudioOutput::say(QString text, int severity)
*/
bool
GAudioOutput
::
alert
(
QString
text
)
{
if
(
!
emergency
||
!
muted
)
{
if
(
!
emergency
||
!
muted
)
{
// Play alert sound
beep
();
// Say alert message
say
(
text
,
2
);
return
true
;
}
else
{
}
else
{
return
false
;
}
}
void
GAudioOutput
::
notifyPositive
()
{
if
(
!
muted
)
{
if
(
!
muted
)
{
// Use QFile to transform path for all OS
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/audio/double_notify.wav"
));
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/
files/
audio/double_notify.wav"
));
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play();
}
...
...
@@ -235,9 +249,10 @@ void GAudioOutput::notifyPositive()
void
GAudioOutput
::
notifyNegative
()
{
if
(
!
muted
)
{
if
(
!
muted
)
{
// Use QFile to transform path for all OS
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/audio/flat_notify.wav"
));
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/
files/
audio/flat_notify.wav"
));
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play();
}
...
...
@@ -252,7 +267,8 @@ void GAudioOutput::notifyNegative()
*/
bool
GAudioOutput
::
startEmergency
()
{
if
(
!
emergency
)
{
if
(
!
emergency
)
{
emergency
=
true
;
// Beep immediately and then start timer
if
(
!
muted
)
beep
();
...
...
@@ -279,9 +295,10 @@ bool GAudioOutput::stopEmergency()
void
GAudioOutput
::
beep
()
{
if
(
!
muted
)
{
if
(
!
muted
)
{
// Use QFile to transform path for all OS
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/audio/alert.wav"
));
QFile
f
(
QCoreApplication
::
applicationDirPath
()
+
QString
(
"/
files/
audio/alert.wav"
));
qDebug
()
<<
"FILE:"
<<
f
.
fileName
();
//m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
//m_media->play();
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
a347a659
...
...
@@ -678,8 +678,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
int
bufferlength
=
0
;
// Output all bytes as hex digits
int
i
;
for
(
i
=
0
;
i
<
size
;
i
++
)
for
(
int
i
=
0
;
i
<
size
;
i
++
)
{
if
(
mavlink_parse_char
(
this
->
id
,
data
[
i
],
&
msg
,
&
comm
))
{
...
...
@@ -687,16 +686,19 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
qDebug
()
<<
"SIMULATION LINK RECEIVED MESSAGE!"
;
emit
messageReceived
(
msg
);
switch
(
msg
.
msgid
)
{
switch
(
msg
.
msgid
)
{
// SET THE SYSTEM MODE
case
MAVLINK_MSG_ID_SET_MODE
:
{
case
MAVLINK_MSG_ID_SET_MODE
:
{
mavlink_set_mode_t
mode
;
mavlink_msg_set_mode_decode
(
&
msg
,
&
mode
);
// Set mode indepent of mode.target
system
.
base_mode
=
mode
.
base_mode
;
}
break
;
case
MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT
:
{
case
MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT
:
{
mavlink_set_local_position_setpoint_t
set
;
mavlink_msg_set_local_position_setpoint_decode
(
&
msg
,
&
set
);
spX
=
set
.
x
;
...
...
@@ -714,7 +716,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
break
;
// EXECUTE OPERATOR ACTIONS
case
MAVLINK_MSG_ID_COMMAND_LONG
:
{
case
MAVLINK_MSG_ID_COMMAND_LONG
:
{
mavlink_command_long_t
action
;
mavlink_msg_command_long_decode
(
&
msg
,
&
action
);
...
...
@@ -756,44 +759,48 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
break
;
#endif
case
MAVLINK_MSG_ID_PARAM_REQUEST_LIST
:
{
case
MAVLINK_MSG_ID_PARAM_REQUEST_LIST
:
{
qDebug
()
<<
"GCS REQUESTED PARAM LIST FROM SIMULATION"
;
mavlink_param_request_list_t
read
;
mavlink_msg_param_request_list_decode
(
&
msg
,
&
read
);
// if (read.target_system == systemId)
// {
// Output all params
// Iterate through all components, through all parameters and emit them
QMap
<
QString
,
float
>::
iterator
i
;
// Iterate through all components / subsystems
int
j
=
0
;
for
(
i
=
onboardParams
.
begin
();
i
!=
onboardParams
.
end
();
++
i
)
{
if
(
j
!=
5
)
{
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
j
);
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
if
(
read
.
target_system
==
systemId
)
{
// Output all params
// Iterate through all components, through all parameters and emit them
QMap
<
QString
,
float
>::
iterator
i
;
// Iterate through all components / subsystems
int
j
=
0
;
for
(
i
=
onboardParams
.
begin
();
i
!=
onboardParams
.
end
();
++
i
)
{
if
(
j
!=
5
)
{
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
MAVLINK_TYPE_FLOAT
,
onboardParams
.
size
(),
j
);
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
}
j
++
;
}
j
++
;
}
qDebug
()
<<
"SIMULATION SENT PARAMETERS TO GCS"
;
//
}
qDebug
()
<<
"SIMULATION SENT PARAMETERS TO GCS"
;
}
}
break
;
case
MAVLINK_MSG_ID_PARAM_SET
:
{
break
;
case
MAVLINK_MSG_ID_PARAM_SET
:
{
// Drop on even milliseconds
if
(
QGC
::
groundTimeMilliseconds
()
%
2
==
0
)
{
if
(
QGC
::
groundTimeMilliseconds
()
%
2
==
0
)
{
qDebug
()
<<
"SIMULATION RECEIVED COMMAND TO SET PARAMETER"
;
mavlink_param_set_t
set
;
mavlink_msg_param_set_decode
(
&
msg
,
&
set
);
// if (set.target_system == systemId)
// {
QString
key
=
QString
((
char
*
)
set
.
param_id
);
if
(
onboardParams
.
contains
(
key
))
{
if
(
onboardParams
.
contains
(
key
))
{
onboardParams
.
remove
(
key
);
onboardParams
.
insert
(
key
,
set
.
param_value
);
...
...
@@ -809,13 +816,15 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
}
break
;
case
MAVLINK_MSG_ID_PARAM_REQUEST_READ
:
{
case
MAVLINK_MSG_ID_PARAM_REQUEST_READ
:
{
qDebug
()
<<
"SIMULATION RECEIVED COMMAND TO SEND PARAMETER"
;
mavlink_param_request_read_t
read
;
mavlink_msg_param_request_read_decode
(
&
msg
,
&
read
);
QByteArray
bytes
((
char
*
)
read
.
param_id
,
MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN
);
QString
key
=
QString
(
bytes
);
if
(
onboardParams
.
contains
(
key
))
{
if
(
onboardParams
.
contains
(
key
))
{
float
paramValue
=
onboardParams
.
value
(
key
);
// Pack message and get size of encoded byte string
...
...
@@ -826,7 +835,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
memcpy
(
stream
+
streampointer
,
buffer
,
bufferlength
);
streampointer
+=
bufferlength
;
//qDebug() << "Sending PARAM" << key;
}
else
if
(
read
.
param_index
<
onboardParams
.
size
())
{
}
else
if
(
read
.
param_index
<
onboardParams
.
size
())
{
key
=
onboardParams
.
keys
().
at
(
read
.
param_index
);
float
paramValue
=
onboardParams
.
value
(
key
);
...
...
@@ -842,8 +853,6 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
break
;
}
}
unsigned
char
v
=
data
[
i
];
fprintf
(
stderr
,
"%02x "
,
v
);
...
...
@@ -851,7 +860,8 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
fprintf
(
stderr
,
"
\n
"
);
readyBufferMutex
.
lock
();
for
(
int
i
=
0
;
i
<
streampointer
;
i
++
)
{
for
(
int
i
=
0
;
i
<
streampointer
;
i
++
)
{
readyBuffer
.
enqueue
(
*
(
stream
+
i
));
}
readyBufferMutex
.
unlock
();
...
...
src/uas/UAS.cc
View file @
a347a659
This diff is collapsed.
Click to expand it.
src/uas/UAS.h
View file @
a347a659
...
...
@@ -218,7 +218,8 @@ protected: //COMMENTS FOR TEST UNIT
bool
batteryRemainingEstimateEnabled
;
///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float
chargeLevel
;
///< Charge level of battery, in percent
int
timeRemaining
;
///< Remaining time calculated based on previous and current
uint8_t
mode
;
///< The current mode of the MAV
uint8_t
mode
;
///< The current mode of the MAV
uint32_t
custom_mode
;
///< The current mode of the MAV
int
status
;
///< The current status of the MAV
uint32_t
navMode
;
///< The current navigation mode of the MAV
quint64
onboardTimeOffset
;
...
...
src/ui/HSIDisplay.cc
View file @
a347a659
...
...
@@ -104,6 +104,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
leftDragStarted
(
false
),
mouseHasMoved
(
false
),
actionPending
(
false
),
directSending
(
false
),
userSetPointSet
(
false
),
userXYSetPointSet
(
false
)
{
...
...
@@ -637,37 +638,53 @@ void HSIDisplay::keyPressEvent(QKeyEvent* event)
statusClearTimer
.
start
();
sendBodySetPointCoordinates
();
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Up
))
else
if
((
event
->
key
()
==
Qt
::
Key_
W
))
{
setBodySetpointCoordinateXY
(
0.5
,
0
);
setBodySetpointCoordinateXY
(
1.0
,
0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Down
))
else
if
((
event
->
key
()
==
Qt
::
Key_
S
))
{
setBodySetpointCoordinateXY
(
-
0.5
,
0
);
setBodySetpointCoordinateXY
(
-
1.0
,
0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Left
))
else
if
((
event
->
key
()
==
Qt
::
Key_
A
))
{
setBodySetpointCoordinateXY
(
0
,
-
0.5
);
setBodySetpointCoordinateXY
(
0
,
-
1.0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Right
))
else
if
((
event
->
key
()
==
Qt
::
Key_
D
))
{
setBodySetpointCoordinateXY
(
0
,
0.5
);
setBodySetpointCoordinateXY
(
0
,
1.0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Plus
))
else
if
((
event
->
key
()
==
Qt
::
Key_
Up
))
{
setBodySetpointCoordinateZ
(
-
0.2
);
setBodySetpointCoordinateXY
(
0
,
0
);
setBodySetpointCoordinateZ
(
-
0.5
+
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_
Minus
))
else
if
((
event
->
key
()
==
Qt
::
Key_
Down
))
{
setBodySetpointCoordinateZ
(
+
0.2
);
setBodySetpointCoordinateZ
(
+
0.5
+
uas
->
getLocalZ
());
setBodySetpointCoordinateXY
(
0
,
0
);
setBodySetpointCoordinateYaw
(
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_L
))
else
if
((
event
->
key
()
==
Qt
::
Key_L
eft
))
{
setBodySetpointCoordinateYaw
(
-
0.1
);
setBodySetpointCoordinateXY
(
0
,
0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
-
0.2
+
uas
->
getYaw
());
}
else
if
((
event
->
key
()
==
Qt
::
Key_R
))
else
if
((
event
->
key
()
==
Qt
::
Key_R
ight
))
{
setBodySetpointCoordinateYaw
(
0.1
);
setBodySetpointCoordinateXY
(
0
,
0
);
setBodySetpointCoordinateZ
(
uas
->
getLocalZ
());
setBodySetpointCoordinateYaw
(
0.2
+
uas
->
getYaw
());
}
HDDisplay
::
keyPressEvent
(
event
);
}
...
...
@@ -811,7 +828,7 @@ void HSIDisplay::sendBodySetPointCoordinates()
double
dx
=
uiXSetCoordinate
-
uas
->
getLocalX
();
double
dy
=
uiYSetCoordinate
-
uas
->
getLocalY
();
double
dz
=
uiZSetCoordinate
-
uas
->
getLocalZ
();
bool
valid
=
(
sqrt
(
dx
*
dx
+
dy
*
dy
+
dz
*
dz
)
<
1
.0
);
//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
bool
valid
=
(
sqrt
(
dx
*
dx
+
dy
*
dy
+
dz
*
dz
)
<
3
.0
);
//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
if
(
valid
)
{
uas
->
setLocalPositionSetpoint
(
uiXSetCoordinate
,
uiYSetCoordinate
,
uiZSetCoordinate
,
uiYawSet
);
...
...
src/ui/HSIDisplay.h
View file @
a347a659
...
...
@@ -175,6 +175,7 @@ protected:
QTimer
statusClearTimer
;
QString
statusMessage
;
bool
actionPending
;
bool
directSending
;
/**
* @brief Private data container class to be used within the HSI widget
...
...
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