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
e4e8e9a5
Commit
e4e8e9a5
authored
Aug 24, 2010
by
Bryan Godbolt
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
working for test
parent
96947527
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
83 additions
and
76 deletions
+83
-76
qgroundcontrol.pro
qgroundcontrol.pro
+5
-3
Core.cc
src/Core.cc
+0
-1
OpalLink.cc
src/comm/OpalLink.cc
+71
-64
OpalLink.h
src/comm/OpalLink.h
+7
-8
No files found.
qgroundcontrol.pro
View file @
e4e8e9a5
...
@@ -153,7 +153,8 @@ HEADERS += src/MG.h \
...
@@ -153,7 +153,8 @@ HEADERS += src/MG.h \
src
/
ui
/
QGCPxImuFirmwareUpdate
.
h
\
src
/
ui
/
QGCPxImuFirmwareUpdate
.
h
\
src
/
comm
/
MAVLinkLightProtocol
.
h
\
src
/
comm
/
MAVLinkLightProtocol
.
h
\
src
/
ui
/
QGCDataPlot2D
.
h
\
src
/
ui
/
QGCDataPlot2D
.
h
\
src
/
ui
/
linechart
/
IncrementalPlot
.
h
src
/
ui
/
linechart
/
IncrementalPlot
.
h
\
src
/
comm
/
OpalRT
.
h
SOURCES
+=
src
/
main
.
cc
\
SOURCES
+=
src
/
main
.
cc
\
src
/
Core
.
cc
\
src
/
Core
.
cc
\
src
/
uas
/
UASManager
.
cc
\
src
/
uas
/
UASManager
.
cc
\
...
@@ -218,8 +219,9 @@ SOURCES += src/main.cc \
...
@@ -218,8 +219,9 @@ SOURCES += src/main.cc \
RESOURCES
=
mavground
.
qrc
RESOURCES
=
mavground
.
qrc
#
Include
RT
-
LAB
Library
#
Include
RT
-
LAB
Library
win32
{
win32
{
LIBS
+=
-
LC
:
\
OPAL
-
RT
\
RT
-
LAB7
.
2.4
\
Common
\
bin
-
lOpalApi
LIBS
+=
-
LC
:
\
OPAL
-
RT
\
RT
-
LAB7
.
2.4
\
Common
\
bin
\
-
lOpalApi
INCLUDEPATH
+=
src
/
lib
/
opalrt
INCLUDEPATH
+=
src
/
lib
/
opalrt
SOURCES
+=
src
/
comm
/
OpalLink
.
cc
SOURCES
+=
src
/
comm
/
OpalLink
.
cc
HEADERS
+=
src
/
comm
/
OpalLink
.
h
HEADERS
+=
src
/
comm
/
OpalLink
.
h
...
...
src/Core.cc
View file @
e4e8e9a5
...
@@ -138,7 +138,6 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
...
@@ -138,7 +138,6 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Add OpalRT Link, but do not connect
// Add OpalRT Link, but do not connect
OpalLink
*
opalLink
=
new
OpalLink
();
OpalLink
*
opalLink
=
new
OpalLink
();
mainWindow
->
addLink
(
opalLink
);
mainWindow
->
addLink
(
opalLink
);
#warning OPAL LINK NOW AUTO CONNECTING IN CORE.CC
#endif
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink
*
simulationLink
=
new
MAVLinkSimulationLink
(
":/demo-log.txt"
);
MAVLinkSimulationLink
*
simulationLink
=
new
MAVLinkSimulationLink
(
":/demo-log.txt"
);
...
...
src/comm/OpalLink.cc
View file @
e4e8e9a5
...
@@ -35,7 +35,7 @@ OpalLink::OpalLink() :
...
@@ -35,7 +35,7 @@ OpalLink::OpalLink() :
heartbeatRate
(
MAVLINK_HEARTBEAT_DEFAULT_RATE
),
heartbeatRate
(
MAVLINK_HEARTBEAT_DEFAULT_RATE
),
m_heartbeatsEnabled
(
true
),
m_heartbeatsEnabled
(
true
),
getSignalsTimer
(
new
QTimer
(
this
)),
getSignalsTimer
(
new
QTimer
(
this
)),
getSignalsPeriod
(
10
00
),
getSignalsPeriod
(
10
),
receiveBuffer
(
new
QQueue
<
QByteArray
>
()),
receiveBuffer
(
new
QQueue
<
QByteArray
>
()),
systemID
(
1
),
systemID
(
1
),
componentID
(
1
)
componentID
(
1
)
...
@@ -74,22 +74,11 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
...
@@ -74,22 +74,11 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
void
OpalLink
::
readBytes
()
void
OpalLink
::
readBytes
()
{
{
receiveDataMutex
.
lock
();
receiveDataMutex
.
lock
();
const
qint64
maxLength
=
2048
;
// qDebug() << "OpalLink::readBytes(): Reading a message. size of buffer: " << receiveBuffer->count();
char
bytes
[
maxLength
];
// QByteArray message = receiveBuffer->dequeue();
qDebug
()
<<
"OpalLink::readBytes(): Reading a message. size of buffer: "
<<
receiveBuffer
->
count
();
QByteArray
message
=
receiveBuffer
->
dequeue
();
if
(
maxLength
<
message
.
size
())
{
qDebug
()
<<
"OpalLink::readBytes:: Buffer Overflow"
;
memcpy
(
bytes
,
message
.
data
(),
maxLength
);
}
else
{
memcpy
(
bytes
,
message
.
data
(),
message
.
size
());
}
emit
bytesReceived
(
this
,
message
);
emit
bytesReceived
(
this
,
receiveBuffer
->
dequeue
()
);
receiveDataMutex
.
unlock
();
receiveDataMutex
.
unlock
();
}
}
...
@@ -104,7 +93,9 @@ void OpalLink::receiveMessage(mavlink_message_t message)
...
@@ -104,7 +93,9 @@ void OpalLink::receiveMessage(mavlink_message_t message)
// If link is connected
// If link is connected
if
(
isConnected
())
if
(
isConnected
())
{
{
receiveDataMutex
.
lock
();
receiveBuffer
->
enqueue
(
QByteArray
(
buffer
,
len
));
receiveBuffer
->
enqueue
(
QByteArray
(
buffer
,
len
));
receiveDataMutex
.
unlock
();
readBytes
();
readBytes
();
}
}
...
@@ -115,7 +106,7 @@ void OpalLink::heartbeat()
...
@@ -115,7 +106,7 @@ void OpalLink::heartbeat()
if
(
m_heartbeatsEnabled
)
if
(
m_heartbeatsEnabled
)
{
{
qDebug
()
<<
"OpalLink::heartbeat(): Generate a heartbeat"
;
//
qDebug() << "OpalLink::heartbeat(): Generate a heartbeat";
mavlink_message_t
beat
;
mavlink_message_t
beat
;
mavlink_msg_heartbeat_pack
(
systemID
,
componentID
,
&
beat
,
MAV_HELICOPTER
,
MAV_AUTOPILOT_GENERIC
);
mavlink_msg_heartbeat_pack
(
systemID
,
componentID
,
&
beat
,
MAV_HELICOPTER
,
MAV_AUTOPILOT_GENERIC
);
receiveMessage
(
beat
);
receiveMessage
(
beat
);
...
@@ -125,41 +116,57 @@ void OpalLink::heartbeat()
...
@@ -125,41 +116,57 @@ void OpalLink::heartbeat()
void
OpalLink
::
getSignals
()
void
OpalLink
::
getSignals
()
{
{
// getSignalsMutex.lock();
// qDebug() << "OpalLink::getSignals(): Attempting to acquire signals";
// qDebug() << "OpalLink::getSignals(): Attempting to acquire signals";
//
//
// unsigned long timeout = 0;
unsigned
long
timeout
=
0
;
// unsigned short acqGroup = 0; //this is actually group 1 in the model
unsigned
short
acqGroup
=
0
;
//this is actually group 1 in the model
// unsigned short allocatedSignals = NUM_OUTPUT_SIGNALS;
unsigned
short
allocatedSignals
=
NUM_OUTPUT_SIGNALS
;
// unsigned short *numSignals = new unsigned short(0);
unsigned
short
*
numSignals
=
new
unsigned
short
(
0
);
// double *timestep = new double(0);
double
*
timestep
=
new
double
(
0
);
// double values[NUM_OUTPUT_SIGNALS] = {};
double
values
[
NUM_OUTPUT_SIGNALS
]
=
{};
// unsigned short *lastValues = new unsigned short(false);
unsigned
short
*
lastValues
=
new
unsigned
short
(
false
);
// unsigned short *decimation = new unsigned short(0);
unsigned
short
*
decimation
=
new
unsigned
short
(
0
);
//
// int returnVal = OpalGetSignals(timeout, acqGroup, allocatedSignals, numSignals, timestep,
while
(
!
(
*
lastValues
))
// values, lastValues, decimation);
{
//
int
returnVal
=
OpalGetSignals
(
timeout
,
acqGroup
,
allocatedSignals
,
numSignals
,
timestep
,
// if (returnVal == EOK )
values
,
lastValues
,
decimation
);
// {
// qDebug() << "OpalLink::getSignals: Timestep=" << *timestep;// << ", Last? " << (bool)(*lastValues);
if
(
returnVal
==
EOK
)
// }
{
// else if (returnVal == EAGAIN)
// qDebug() << "OpalLink::getSignals: Timestep=" << *timestep;// << ", Last? " << (bool)(*lastValues);
// {
mavlink_message_t
local_position
;
// qDebug() << "OpalLink::getSignals: Data was not ready";
mavlink_msg_local_position_pack
(
systemID
,
componentID
,
&
local_position
,
// }
(
*
timestep
)
*
1000000
,
// // if returnVal == EAGAIN => data just wasn't ready
values
[
OpalRT
::
X_POS
],
// else if (returnVal != EAGAIN)
values
[
OpalRT
::
Y_POS
],
// {
values
[
OpalRT
::
Z_POS
],
// getSignalsTimer->stop();
values
[
OpalRT
::
X_VEL
],
// displayErrorMsg();
values
[
OpalRT
::
Y_VEL
],
// }
values
[
OpalRT
::
Z_VEL
]);
// /* deallocate used memory */
receiveMessage
(
local_position
);
//
}
// delete timestep;
else
if
(
returnVal
==
EAGAIN
)
// delete lastValues;
{
// delete lastValues;
// qDebug() << "OpalLink::getSignals: Data was not ready";
// delete decimation;
}
// if returnVal == EAGAIN => data just wasn't ready
else
if
(
returnVal
!=
EAGAIN
)
{
getSignalsTimer
->
stop
();
displayErrorMsg
();
}
}
/* deallocate used memory */
delete
numSignals
;
delete
timestep
;
delete
lastValues
;
delete
decimation
;
// getSignalsMutex.unlock();
}
}
...
@@ -170,7 +177,7 @@ void OpalLink::getSignals()
...
@@ -170,7 +177,7 @@ void OpalLink::getSignals()
*/
*/
void
OpalLink
::
run
()
void
OpalLink
::
run
()
{
{
qDebug
()
<<
"OpalLink::run():: Starting the thread"
;
//
qDebug() << "OpalLink::run():: Starting the thread";
}
}
int
OpalLink
::
getId
()
int
OpalLink
::
getId
()
...
@@ -202,18 +209,18 @@ bool OpalLink::connect()
...
@@ -202,18 +209,18 @@ bool OpalLink::connect()
short
modelState
;
short
modelState
;
/// \todo allow configuration of instid in window
/// \todo allow configuration of instid in window
//
if (OpalConnect(101, false, &modelState) == EOK)
if
(
OpalConnect
(
101
,
false
,
&
modelState
)
==
EOK
)
//
{
{
connectState
=
true
;
connectState
=
true
;
emit
connected
();
emit
connected
();
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
getSignalsTimer
->
start
(
getSignalsPeriod
);
getSignalsTimer
->
start
(
getSignalsPeriod
);
//
}
}
//
else
else
//
{
{
//
connectState = false;
connectState
=
false
;
//
displayErrorMsg();
displayErrorMsg
();
//
}
}
emit
connected
(
connectState
);
emit
connected
(
connectState
);
return
connectState
;
return
connectState
;
...
@@ -235,11 +242,11 @@ void OpalLink::displayErrorMsg()
...
@@ -235,11 +242,11 @@ void OpalLink::displayErrorMsg()
void
OpalLink
::
setLastErrorMsg
()
void
OpalLink
::
setLastErrorMsg
()
{
{
//
char buf[512];
char
buf
[
512
];
//
unsigned short len;
unsigned
short
len
;
//
OpalGetLastErrMsg(buf, sizeof(buf), &len);
OpalGetLastErrMsg
(
buf
,
sizeof
(
buf
),
&
len
);
//
lastErrorMsg.clear();
lastErrorMsg
.
clear
();
//
lastErrorMsg.append(buf);
lastErrorMsg
.
append
(
buf
);
}
}
...
...
src/comm/OpalLink.h
View file @
e4e8e9a5
...
@@ -44,15 +44,13 @@ This file is part of the QGROUNDCONTROL project
...
@@ -44,15 +44,13 @@ This file is part of the QGROUNDCONTROL project
#include "mavlink.h"
#include "mavlink.h"
#include "mavlink_types.h"
#include "mavlink_types.h"
#include "configuration.h"
#include "configuration.h"
#include "OpalRT.h"
#include "errno.h"
#include "errno.h"
#ifdef OPAL_RT
#include "OpalApi.h"
#endif
// FIXME
//#include "OpalApi.h"
...
@@ -66,9 +64,9 @@ This file is part of the QGROUNDCONTROL project
...
@@ -66,9 +64,9 @@ This file is part of the QGROUNDCONTROL project
#define NUM_OUTPUT_SIGNALS 6
#define NUM_OUTPUT_SIGNALS 6
/**
/**
* @brief Interface to O
PAL-
RT targets
* @brief Interface to O
pal
RT targets
*
*
* This is an interface to the Opal
-
RT hardware-in-the-loop (HIL) simulator.
* This is an interface to the OpalRT hardware-in-the-loop (HIL) simulator.
* This class receives MAVLink packets as if it is a true link, but it
* This class receives MAVLink packets as if it is a true link, but it
* interprets the packets internally, and calls the appropriate api functions.
* interprets the packets internally, and calls the appropriate api functions.
*
*
...
@@ -144,6 +142,7 @@ protected:
...
@@ -144,6 +142,7 @@ protected:
QMutex
statisticsMutex
;
QMutex
statisticsMutex
;
QMutex
receiveDataMutex
;
QMutex
receiveDataMutex
;
// QMutex getSignalsMutex;
QString
lastErrorMsg
;
QString
lastErrorMsg
;
void
setLastErrorMsg
();
void
setLastErrorMsg
();
void
displayErrorMsg
();
void
displayErrorMsg
();
...
...
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