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
ca963db2
Commit
ca963db2
authored
Apr 20, 2010
by
lm
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of git@pixhawk.ethz.ch:groundcontrol
parents
4e8f2906
dfa6906f
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
87 additions
and
102 deletions
+87
-102
qgroundcontrol.pri
qgroundcontrol.pri
+2
-2
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+26
-49
MAVLinkSimulationLink.h
src/comm/MAVLinkSimulationLink.h
+2
-3
HUD.cc
src/ui/HUD.cc
+29
-21
HUD.h
src/ui/HUD.h
+1
-1
MainWindow.cc
src/ui/MainWindow.cc
+8
-24
MainWindow.h
src/ui/MainWindow.h
+2
-1
MainWindow.ui
src/ui/MainWindow.ui
+17
-1
No files found.
qgroundcontrol.pri
View file @
ca963db2
...
...
@@ -59,8 +59,8 @@ macx {
# Enable function-profiling with the OS X saturn tool
debug {
QMAKE_CXXFLAGS += -finstrument-functions
LIBS += -lSaturn
#
QMAKE_CXXFLAGS += -finstrument-functions
#
LIBS += -lSaturn
}
} else {
# x64 Mac OS X Snow Leopard 10.6 and later
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
ca963db2
...
...
@@ -504,26 +504,26 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
message_action_decode
(
&
msg
,
&
action
);
switch
(
action
.
action
)
{
case
MAV_ACTION_LAUNCH
:
case
MAV_ACTION_LAUNCH
:
status
.
status
=
MAV_STATE_ACTIVE
;
status
.
mode
=
MAV_MODE_AUTO
;
break
;
case
MAV_ACTION_RETURN
:
case
MAV_ACTION_RETURN
:
status
.
status
=
MAV_STATE_LANDING
;
break
;
case
MAV_ACTION_MOTORS_START
:
case
MAV_ACTION_MOTORS_START
:
status
.
status
=
MAV_STATE_ACTIVE
;
status
.
mode
=
MAV_MODE_LOCKED
;
break
;
case
MAV_ACTION_MOTORS_STOP
:
case
MAV_ACTION_MOTORS_STOP
:
status
.
status
=
MAV_STATE_STANDBY
;
status
.
mode
=
MAV_MODE_LOCKED
;
break
;
case
MAV_ACTION_EMCY_KILL
:
case
MAV_ACTION_EMCY_KILL
:
status
.
status
=
MAV_STATE_EMERGENCY
;
status
.
mode
=
MAV_MODE_MANUAL
;
break
;
case
MAV_ACTION_SHUTDOWN
:
case
MAV_ACTION_SHUTDOWN
:
status
.
status
=
MAV_STATE_POWEROFF
;
status
.
mode
=
MAV_MODE_LOCKED
;
break
;
...
...
@@ -579,48 +579,6 @@ void MAVLinkSimulationLink::readBytes(char* const data, qint64 maxLength) {
// }
}
/**
* Set the maximum time deviation noise. This amount (in milliseconds) is
* the maximum time offset (+/-) from the specified message send rate.
*
* @param milliseconds The maximum time offset (in milliseconds)
*
* @bug The current implementation might induce one milliseconds additional
* discrepancy, this will be fixed by multithreading
**/
void
MAVLinkSimulationLink
::
setMaximumTimeNoise
(
int
milliseconds
)
{
maxTimeNoise
=
milliseconds
;
}
/**
* Add or subtract a pseudo random time offset. The maximum time offset is
* defined by setMaximumTimeNoise().
*
* @see setMaximumTimeNoise()
**/
void
MAVLinkSimulationLink
::
addTimeNoise
()
{
/* Calculate the time deviation */
if
(
maxTimeNoise
==
0
)
{
/* Don't do expensive calculations if no noise is desired */
timer
->
setInterval
(
rate
);
}
else
{
/* Calculate random time noise (gauss distribution):
*
* (1) (2 * rand()) / RAND_MAX: Number between 0 and 2
* (induces numerical noise through floating point representation,
* ignored here)
*
* (2) ((2 * rand()) / RAND_MAX) - 1: Number between -1 and 1
*
* (3) Complete term: Number between -maxTimeNoise and +maxTimeNoise
*/
double
timeDeviation
=
(((
2
*
rand
())
/
RAND_MAX
)
-
1
)
*
maxTimeNoise
;
timer
->
setInterval
(
static_cast
<
int
>
(
rate
+
floor
(
timeDeviation
)));
}
}
/**
* Disconnect the connection.
*
...
...
@@ -636,7 +594,7 @@ bool MAVLinkSimulationLink::disconnect() {
emit
disconnected
();
exit
();
//
exit();
}
return
true
;
...
...
@@ -657,6 +615,25 @@ bool MAVLinkSimulationLink::connect()
return
true
;
}
/**
* Connect the link.
*
* @param connect true connects the link, false disconnects it
* @return True if connection has been established, false if connection
* couldn't be established.
**/
bool
MAVLinkSimulationLink
::
connectLink
(
bool
connect
)
{
_isConnected
=
connect
;
if
(
connect
)
{
this
->
connect
();
}
return
true
;
}
/**
* Check if connection is active.
*
...
...
src/comm/MAVLinkSimulationLink.h
View file @
ca963db2
...
...
@@ -84,6 +84,7 @@ public slots:
void
writeBytes
(
const
char
*
data
,
qint64
size
);
void
readBytes
(
char
*
const
data
,
qint64
maxLength
);
void
mainloop
();
bool
connectLink
(
bool
connect
);
protected:
...
...
@@ -116,11 +117,9 @@ protected:
qint64
timeOffset
;
sys_status_t
status
;
void
setMaximumTimeNoise
(
int
milliseconds
);
void
addTimeNoise
();
void
enqueue
(
uint8_t
*
stream
,
uint8_t
*
index
,
mavlink_message_t
*
msg
);
signals:
signals:
void
valueChanged
(
int
uasId
,
QString
curve
,
double
value
,
quint64
usec
);
};
...
...
src/ui/HUD.cc
View file @
ca963db2
...
...
@@ -65,7 +65,7 @@ inline bool isinf(T value)
* @param parent
*/
HUD
::
HUD
(
int
width
,
int
height
,
QWidget
*
parent
)
:
QGLWidget
(
parent
),
:
QGLWidget
(
QGLFormat
(
QGL
::
SampleBuffers
),
parent
),
uas
(
NULL
),
values
(
QMap
<
QString
,
float
>
()),
valuesDot
(
QMap
<
QString
,
float
>
()),
...
...
@@ -127,7 +127,7 @@ HUD::HUD(int width, int height, QWidget* parent)
// Refresh timer
refreshTimer
->
setInterval
(
40
);
// 25 Hz
connect
(
refreshTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
repaint
()));
connect
(
refreshTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
update
()));
// Resize to correct size and fill with image
resize
(
fill
.
size
());
...
...
@@ -171,8 +171,8 @@ void HUD::stop()
void
HUD
::
updateValue
(
UASInterface
*
uas
,
QString
name
,
double
value
,
quint64
msec
)
{
//
if (this->uas == uas)
//{
//
UAS is not needed
Q_UNUSED
(
uas
);
if
(
!
isnan
(
value
)
&&
!
isinf
(
value
))
{
...
...
@@ -316,6 +316,8 @@ void HUD::updateSpeed(UASInterface* uas,double x,double y,double z,quint64 times
*/
void
HUD
::
updateState
(
UASInterface
*
uas
,
QString
state
)
{
// Only one UAS is connected at a time
Q_UNUSED
(
uas
);
this
->
state
=
state
;
}
...
...
@@ -327,6 +329,8 @@ void HUD::updateState(UASInterface* uas,QString state)
*/
void
HUD
::
updateMode
(
UASInterface
*
uas
,
QString
mode
)
{
// Only one UAS is connected at a time
Q_UNUSED
(
uas
);
this
->
mode
=
mode
;
}
...
...
@@ -467,9 +471,9 @@ void HUD::initializeGL()
}
else
{
//
glDisable(GL_BLEND);
//
glDisable(GL_POINT_SMOOTH);
//
glDisable(GL_LINE_SMOOTH);
glDisable
(
GL_BLEND
);
glDisable
(
GL_POINT_SMOOTH
);
glDisable
(
GL_LINE_SMOOTH
);
}
}
...
...
@@ -510,18 +514,16 @@ void HUD::paintRollPitchStrips()
}
void
HUD
::
paintGL
()
{
}
void
HUD
::
paintEvent
(
QPaintEvent
*
event
)
{
// Event is not needed
Q_UNUSED
(
event
);
// Read out most important values to limit hash table lookups
static
float
roll
=
0.0
;
static
float
pitch
=
0.0
;
static
float
yaw
=
0.0
;
// Read out most important values to limit hash table lookups
roll
=
roll
*
0.5
+
0.5
*
values
.
value
(
"roll"
,
0.0
f
);
pitch
=
pitch
*
0.5
+
0.5
*
values
.
value
(
"pitch"
,
0.0
f
);
yaw
=
yaw
*
0.5
+
0.5
*
values
.
value
(
"yaw"
,
0.0
f
);
...
...
@@ -536,22 +538,29 @@ void HUD::paintEvent(QPaintEvent *event)
// OPEN GL PAINTING
// Store model view matrix to be able to reset it to the previous state
makeCurrent
();
//setupViewport(width(), height());
glMatrixMode
(
GL_MODELVIEW
);
glPushMatrix
();
glClear
(
GL_COLOR_BUFFER_BIT
|
GL_DEPTH_BUFFER_BIT
);
// Blue / Brown background
if
(
noCamera
)
paintCenterBackground
(
roll
,
pitch
,
yaw
);
glMatrixMode
(
GL_MODELVIEW
);
glPopMatrix
();
// END OF OPENGL PAINTING
//glEnable(GL_MULTISAMPLE);
// QT PAINTING
makeCurrent
();
QPainter
painter
;
painter
.
begin
(
this
);
painter
.
setRenderHint
(
QPainter
::
Antialiasing
);
painter
.
setRenderHint
(
QPainter
::
Antialiasing
,
true
);
painter
.
setRenderHint
(
QPainter
::
HighQualityAntialiasing
,
true
);
//
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
painter
.
translate
((
this
->
vwidth
/
2.0
+
xCenterOffset
)
*
scalingFactor
,
(
this
->
vheight
/
2.0
+
yCenterOffset
)
*
scalingFactor
);
...
...
@@ -687,11 +696,10 @@ void HUD::paintEvent(QPaintEvent *event)
// PITCH
paintPitchLines
((
pitch
/
M_PI
)
*
180.0
f
,
&
painter
);
painter
.
end
();
//glDisable(GL_MULTISAMPLE);
glFlush
();
//glFlush();
}
/*
...
...
@@ -1379,7 +1387,7 @@ void HUD::finishImage()
void
HUD
::
commitRawDataToGL
()
{
//
qDebug() << __FILE__ << __LINE__ << "Copying raw data to GL buffer:" << rawImage << receivedWidth << receivedHeight << image->format();
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"Copying raw data to GL buffer:"
<<
rawImage
<<
receivedWidth
<<
receivedHeight
<<
image
->
format
();
if
(
image
!=
NULL
)
{
QImage
::
Format
format
=
image
->
format
();
...
...
@@ -1410,7 +1418,7 @@ void HUD::commitRawDataToGL()
//qDebug() << "Now buffer 1";
}
}
update
GL
();
update
();
}
void
HUD
::
saveImage
(
QString
fileName
)
...
...
src/ui/HUD.h
View file @
ca963db2
...
...
@@ -58,7 +58,7 @@ public:
public
slots
:
void
initializeGL
();
void
paintGL
();
//
void paintGL();
/** @brief Start updating the view at 30Hz */
void
start
();
...
...
src/ui/MainWindow.cc
View file @
ca963db2
...
...
@@ -146,9 +146,6 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent)
// Add status bar
setStatusBar
(
createStatusBar
());
// Create actions
connectActions
();
// Set the application style (not the same as a style sheet)
// Set the style to Plastique
qApp
->
setStyle
(
"plastique"
);
...
...
@@ -167,12 +164,15 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent)
udpLink
->
connect
();
simulationLink
=
new
MAVLinkSimulationLink
(
MG
::
DIR
::
getSupportFilesDirectory
()
+
"/demo-log.txt"
);
//
connect(simulationLink, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
connect
(
simulationLink
,
SIGNAL
(
valueChanged
(
int
,
QString
,
double
,
quint64
)),
linechart
,
SLOT
(
appendData
(
int
,
QString
,
double
,
quint64
)));
LinkManager
::
instance
()
->
addProtocol
(
simulationLink
,
mavlink
);
//CommConfigurationWindow* simulationWidget = new CommConfigurationWindow(simulationLink, mavlink, this);
//ui.menuNetwork->addAction(commWidget->getAction());
//simulationLink->connect();
// Create actions
connectActions
();
// Load widgets and show application window
loadWidgets
();
...
...
@@ -287,6 +287,7 @@ void MainWindow::connectActions()
// Joystick configuration
connect
(
ui
.
actionJoystickSettings
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
configure
()));
connect
(
ui
.
actionSimulate
,
SIGNAL
(
triggered
(
bool
)),
simulationLink
,
SLOT
(
connectLink
(
bool
)));
}
void
MainWindow
::
configure
()
...
...
@@ -338,6 +339,9 @@ void MainWindow::UASCreated(UASInterface* uas)
reloadStylesheet
();
}
/**
* Clears the current view completely
*/
void
MainWindow
::
clearView
()
{
// Halt HUD
...
...
@@ -502,26 +506,6 @@ void MainWindow::removeCommConfAct(QAction* action)
ui.menuNetwork->removeAction(action);
}*/
//void MainWindow::startUAS()
//{
// UASManager::instance()->getActiveUAS()->launch();
//}
//
//void MainWindow::returnUAS()
//{
// UASManager::instance()->getActiveUAS()->home();
//}
//
//void MainWindow::stopUAS()
//{
// UASManager::instance()->getActiveUAS()->emergencySTOP();
//}
//
//void MainWindow::killUAS()
//{
// UASManager::instance()->getActiveUAS()->emergencyKILL();
//}
void
MainWindow
::
runTests
()
{
// TODO Remove after debugging: Add fake data
...
...
src/ui/MainWindow.h
View file @
ca963db2
...
...
@@ -47,6 +47,7 @@ This file is part of the PIXHAWK project
#include "CameraView.h"
#include "UASListWidget.h"
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
#include "AS4Protocol.h"
#include "ObjectDetectionView.h"
#include "HUD.h"
...
...
@@ -142,7 +143,7 @@ protected:
MAVLinkProtocol
*
mavlink
;
AS4Protocol
*
as4link
;
LinkInterface
*
simulationLink
;
MAVLinkSimulationLink
*
simulationLink
;
LinkInterface
*
udpLink
;
QDockWidget
*
controlDock
;
...
...
src/ui/MainWindow.ui
View file @
ca963db2
...
...
@@ -35,7 +35,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
1000
</width>
<height>
2
5
</height>
<height>
2
2
</height>
</rect>
</property>
<widget
class=
"QMenu"
name=
"menuMGround"
>
...
...
@@ -43,6 +43,7 @@
<string>
File
</string>
</property>
<addaction
name=
"actionJoystickSettings"
/>
<addaction
name=
"actionSimulate"
/>
<addaction
name=
"separator"
/>
<addaction
name=
"actionExit"
/>
</widget>
...
...
@@ -225,6 +226,21 @@
<string>
Show settings view
</string>
</property>
</action>
<action
name=
"actionSimulate"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
</property>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/control/launch.svg
</normaloff>
:/images/control/launch.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Simulate
</string>
</property>
<property
name=
"toolTip"
>
<string>
Simulate one vehicle to test and evaluate this application
</string>
</property>
</action>
</widget>
<layoutdefault
spacing=
"6"
margin=
"11"
/>
<resources>
...
...
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