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
e9c9937f
Commit
e9c9937f
authored
Sep 03, 2012
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added editable link forwarding
parent
406c262b
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
83 additions
and
64 deletions
+83
-64
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+74
-58
QGCXPlaneLink.h
src/comm/QGCXPlaneLink.h
+6
-6
MAVLinkSettingsWidget.ui
src/ui/MAVLinkSettingsWidget.ui
+3
-0
No files found.
src/comm/QGCXPlaneLink.cc
View file @
e9c9937f
...
...
@@ -38,16 +38,15 @@ This file is part of the QGROUNDCONTROL project
#include <QHostInfo>
#include "MainWindow.h"
QGCXPlaneLink
::
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
,
QHostAddress
host
,
quint16
p
ort
)
:
QGCXPlaneLink
::
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
,
QHostAddress
localHost
,
quint16
localP
ort
)
:
process
(
NULL
),
terraSync
(
NULL
)
{
this
->
host
=
h
ost
;
this
->
port
=
port
+
mav
->
getUASID
()
;
this
->
localHost
=
localH
ost
;
this
->
localPort
=
localPort
/*+mav->getUASID()*/
;
this
->
connectState
=
false
;
this
->
currentPort
=
48000
+
mav
->
getUASID
();
this
->
mav
=
mav
;
this
->
name
=
tr
(
"X-Plane Link (
port:%1)"
).
arg
(
p
ort
);
this
->
name
=
tr
(
"X-Plane Link (
localPort:%1)"
).
arg
(
localP
ort
);
setRemoteHost
(
remoteHost
);
}
...
...
@@ -68,9 +67,9 @@ void QGCXPlaneLink::run()
exec
();
}
void
QGCXPlaneLink
::
setPort
(
int
p
ort
)
void
QGCXPlaneLink
::
setPort
(
int
localP
ort
)
{
this
->
port
=
p
ort
;
this
->
localPort
=
localP
ort
;
disconnectSimulation
();
connectSimulation
();
}
...
...
@@ -102,40 +101,40 @@ void QGCXPlaneLink::processError(QProcess::ProcessError err)
}
/**
* @param
host Hostname in standard formatting, e.g. localh
ost:14551 or 192.168.1.1:14551
* @param
localHost Hostname in standard formatting, e.g. locallocalH
ost:14551 or 192.168.1.1:14551
*/
void
QGCXPlaneLink
::
setRemoteHost
(
const
QString
&
h
ost
)
void
QGCXPlaneLink
::
setRemoteHost
(
const
QString
&
localH
ost
)
{
if
(
h
ost
.
contains
(
":"
))
if
(
localH
ost
.
contains
(
":"
))
{
//qDebug() << "HOST: " <<
h
ost.split(":").first();
QHostInfo
info
=
QHostInfo
::
fromName
(
h
ost
.
split
(
":"
).
first
());
//qDebug() << "HOST: " <<
localH
ost.split(":").first();
QHostInfo
info
=
QHostInfo
::
fromName
(
localH
ost
.
split
(
":"
).
first
());
if
(
info
.
error
()
==
QHostInfo
::
NoError
)
{
// Add
h
ost
QList
<
QHostAddress
>
h
ostAddresses
=
info
.
addresses
();
// Add
localH
ost
QList
<
QHostAddress
>
localH
ostAddresses
=
info
.
addresses
();
QHostAddress
address
;
for
(
int
i
=
0
;
i
<
h
ostAddresses
.
size
();
i
++
)
for
(
int
i
=
0
;
i
<
localH
ostAddresses
.
size
();
i
++
)
{
// Exclude loopback IPv4 and all IPv6 addresses
if
(
!
h
ostAddresses
.
at
(
i
).
toString
().
contains
(
":"
))
if
(
!
localH
ostAddresses
.
at
(
i
).
toString
().
contains
(
":"
))
{
address
=
h
ostAddresses
.
at
(
i
);
address
=
localH
ostAddresses
.
at
(
i
);
}
}
current
Host
=
address
;
remote
Host
=
address
;
//qDebug() << "Address:" << address.toString();
// Set
p
ort according to user input
currentPort
=
h
ost
.
split
(
":"
).
last
().
toInt
();
// Set
localP
ort according to user input
remotePort
=
localH
ost
.
split
(
":"
).
last
().
toInt
();
}
}
else
{
QHostInfo
info
=
QHostInfo
::
fromName
(
h
ost
);
QHostInfo
info
=
QHostInfo
::
fromName
(
localH
ost
);
if
(
info
.
error
()
==
QHostInfo
::
NoError
)
{
// Add
h
ost
current
Host
=
info
.
addresses
().
first
();
// Add
localH
ost
remote
Host
=
info
.
addresses
().
first
();
}
}
...
...
@@ -175,11 +174,11 @@ void QGCXPlaneLink::writeBytes(const char* data, qint64 size)
ascii
.
append
(
219
);
}
}
qDebug
()
<<
"Sent"
<<
size
<<
"bytes to"
<<
currentHost
.
toString
()
<<
":"
<<
current
Port
<<
"data:"
;
qDebug
()
<<
"Sent"
<<
size
<<
"bytes to"
<<
remoteHost
.
toString
()
<<
":"
<<
remote
Port
<<
"data:"
;
qDebug
()
<<
bytes
;
qDebug
()
<<
"ASCII:"
<<
ascii
;
#endif
if
(
connectState
&&
socket
)
socket
->
writeDatagram
(
data
,
size
,
currentHost
,
current
Port
);
if
(
connectState
&&
socket
)
socket
->
writeDatagram
(
data
,
size
,
remoteHost
,
remote
Port
);
}
/**
...
...
@@ -201,20 +200,37 @@ void QGCXPlaneLink::readBytes()
QByteArray
b
(
data
,
s
);
// Print string
QString
state
(
b
);
//qDebug() << "FG LINK GOT:" << state;
/*// Print string
QString state(b)*/
;
QStringList
values
=
state
.
split
(
"
\t
"
);
// Calculate the number of data segments a 36 bytes
// XPlane always has 5 bytes header: 'DATA@'
unsigned
nsegs
=
(
s
-
5
)
/
36
;
// Check length
if
(
values
.
size
()
!=
17
)
qDebug
()
<<
"XPLANE:"
<<
"LEN:"
<<
s
<<
"segs:"
<<
nsegs
;
union
dataconv
{
char
c
[
8
];
float
f
;
double
d
;
int
i
;
}
u
;
for
(
unsigned
i
=
0
;
i
<
nsegs
;
i
++
)
{
qDebug
()
<<
"RETURN LENGTH MISMATCHING EXPECTED"
<<
17
<<
"BUT GOT"
<<
values
.
size
();
qDebug
()
<<
state
;
return
;
// Get index
unsigned
ioff
=
(
5
+
i
*
36
);
memcpy
(
&
(
u
.
i
),
data
+
ioff
,
sizeof
(
u
.
i
));
qDebug
()
<<
"ind:"
<<
u
.
i
;
unsigned
doff
=
ioff
+
sizeof
(
u
.
i
);
unsigned
dsize
=
sizeof
(
u
.
d
);
memcpy
(
&
(
u
.
d
),
data
+
doff
,
dsize
);
doff
+=
dsize
;
qDebug
()
<<
"val1:"
<<
u
.
d
;
}
return
;
// Parse string
double
time
;
float
roll
,
pitch
,
yaw
,
rollspeed
,
pitchspeed
,
yawspeed
;
...
...
@@ -222,26 +238,26 @@ void QGCXPlaneLink::readBytes()
double
vx
,
vy
,
vz
,
xacc
,
yacc
,
zacc
;
double
airspeed
;
time
=
values
.
at
(
0
).
toDouble
();
lat
=
values
.
at
(
1
).
toDouble
();
lon
=
values
.
at
(
2
).
toDouble
();
alt
=
values
.
at
(
3
).
toDouble
();
roll
=
values
.
at
(
4
).
toDouble
();
pitch
=
values
.
at
(
5
).
toDouble
();
yaw
=
values
.
at
(
6
).
toDouble
();
rollspeed
=
values
.
at
(
7
).
toDouble
();
pitchspeed
=
values
.
at
(
8
).
toDouble
();
yawspeed
=
values
.
at
(
9
).
toDouble
();
//
time = values.at(0).toDouble();
//
lat = values.at(1).toDouble();
//
lon = values.at(2).toDouble();
//
alt = values.at(3).toDouble();
//
roll = values.at(4).toDouble();
//
pitch = values.at(5).toDouble();
//
yaw = values.at(6).toDouble();
//
rollspeed = values.at(7).toDouble();
//
pitchspeed = values.at(8).toDouble();
//
yawspeed = values.at(9).toDouble();
xacc
=
values
.
at
(
10
).
toDouble
();
yacc
=
values
.
at
(
11
).
toDouble
();
zacc
=
values
.
at
(
12
).
toDouble
();
//
xacc = values.at(10).toDouble();
//
yacc = values.at(11).toDouble();
//
zacc = values.at(12).toDouble();
vx
=
values
.
at
(
13
).
toDouble
();
vy
=
values
.
at
(
14
).
toDouble
();
vz
=
values
.
at
(
15
).
toDouble
();
//
vx = values.at(13).toDouble();
//
vy = values.at(14).toDouble();
//
vz = values.at(15).toDouble();
airspeed
=
values
.
at
(
16
).
toDouble
();
//
airspeed = values.at(16).toDouble();
// Send updated state
emit
hilStateChanged
(
QGC
::
groundTimeUsecs
(),
roll
,
pitch
,
yaw
,
rollspeed
,
...
...
@@ -317,7 +333,7 @@ bool QGCXPlaneLink::connectSimulation()
{
if
(
!
mav
)
return
false
;
socket
=
new
QUdpSocket
(
this
);
connectState
=
socket
->
bind
(
host
,
p
ort
);
connectState
=
socket
->
bind
(
localHost
,
localP
ort
);
QObject
::
connect
(
socket
,
SIGNAL
(
readyRead
()),
this
,
SLOT
(
readBytes
()));
...
...
@@ -406,7 +422,7 @@ bool QGCXPlaneLink::connectSimulation()
// if (!sane) return false;
// // --atlas=socket,out,1,local
h
ost,5505,udp
// // --atlas=socket,out,1,local
localH
ost,5505,udp
// // terrasync -p 5505 -S -d /usr/local/share/TerraSync
// processCall << QString("--fg-root=%1").arg(fgRoot);
...
...
@@ -414,15 +430,15 @@ bool QGCXPlaneLink::connectSimulation()
// if (mav->getSystemType() == MAV_TYPE_QUADROTOR)
// {
// // FIXME ADD QUAD-Specific protocol here
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
p
ort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
current
Port);
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
localP
ort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
remote
Port);
// }
// else
// {
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
p
ort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
current
Port);
// processCall << QString("--generic=socket,out,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
localP
ort);
// processCall << QString("--generic=socket,in,50,127.0.0.1,%1,udp,qgroundcontrol").arg(
remote
Port);
// }
// processCall << "--atlas=socket,out,1,local
h
ost,5505,udp";
// processCall << "--atlas=socket,out,1,local
localH
ost,5505,udp";
// processCall << "--in-air";
// processCall << "--roll=0";
// processCall << "--pitch=0";
...
...
src/comm/QGCXPlaneLink.h
View file @
e9c9937f
...
...
@@ -49,13 +49,13 @@ class QGCXPlaneLink : public QGCHilLink
//Q_INTERFACES(QGCXPlaneLinkInterface:LinkInterface)
public:
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
=
QString
(
"127.0.0.1:49000"
),
QHostAddress
host
=
QHostAddress
::
Any
,
quint16
p
ort
=
49005
);
QGCXPlaneLink
(
UASInterface
*
mav
,
QString
remoteHost
=
QString
(
"127.0.0.1:49000"
),
QHostAddress
localHost
=
QHostAddress
::
Any
,
quint16
localP
ort
=
49005
);
~
QGCXPlaneLink
();
bool
isConnected
();
qint64
bytesAvailable
();
int
getPort
()
const
{
return
p
ort
;
return
localP
ort
;
}
/**
...
...
@@ -90,10 +90,10 @@ public slots:
protected:
QString
name
;
QHostAddress
h
ost
;
QHostAddress
currentHos
t
;
quint16
currentPor
t
;
quint16
p
ort
;
QHostAddress
localH
ost
;
quint16
localPor
t
;
QHostAddress
remoteHos
t
;
quint16
remoteP
ort
;
int
id
;
QUdpSocket
*
socket
;
bool
connectState
;
...
...
src/ui/MAVLinkSettingsWidget.ui
View file @
e9c9937f
...
...
@@ -336,6 +336,9 @@
</item>
<item
row=
"19"
column=
"1"
colspan=
"2"
>
<widget
class=
"QComboBox"
name=
"droneOSComboBox"
>
<property
name=
"editable"
>
<bool>
true
</bool>
</property>
<item>
<property
name=
"text"
>
<string>
mavlink.droneos.com:14555
</string>
...
...
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