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
6af9a170
Commit
6af9a170
authored
9 years ago
by
dogmaphobic
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
More Android work...
parent
db135056
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
148 additions
and
175 deletions
+148
-175
UsbDeviceJNI.java
android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java
+2
-2
qserialport_android.cpp
libs/qtandroidserialport/src/qserialport_android.cpp
+134
-171
qserialportinfo_android.cpp
libs/qtandroidserialport/src/qserialportinfo_android.cpp
+6
-0
QGCApplication.cc
src/QGCApplication.cc
+2
-0
QGCFileDialog.cc
src/QGCFileDialog.cc
+2
-2
MainWindow.cc
src/ui/MainWindow.cc
+2
-0
No files found.
android/src/org/qgroundcontrol/qgchelper/UsbDeviceJNI.java
View file @
6af9a170
...
@@ -60,6 +60,7 @@ public class UsbDeviceJNI extends QtActivity
...
@@ -60,6 +60,7 @@ public class UsbDeviceJNI extends QtActivity
// USED TO DETECT WHEN A DEVICE HAS BEEN UNPLUGGED
// USED TO DETECT WHEN A DEVICE HAS BEEN UNPLUGGED
private
BroadcastReceiver
m_UsbReceiver
=
null
;
private
BroadcastReceiver
m_UsbReceiver
=
null
;
private
final
static
ExecutorService
m_Executor
=
Executors
.
newSingleThreadExecutor
();
private
final
static
ExecutorService
m_Executor
=
Executors
.
newSingleThreadExecutor
();
private
static
final
String
TAG
=
"QGC_UsbDeviceJNI"
;
private
final
static
UsbIoManager
.
Listener
m_Listener
=
private
final
static
UsbIoManager
.
Listener
m_Listener
=
new
UsbIoManager
.
Listener
()
new
UsbIoManager
.
Listener
()
...
@@ -67,6 +68,7 @@ public class UsbDeviceJNI extends QtActivity
...
@@ -67,6 +68,7 @@ public class UsbDeviceJNI extends QtActivity
@Override
@Override
public
void
onRunError
(
Exception
eA
,
int
userDataA
)
public
void
onRunError
(
Exception
eA
,
int
userDataA
)
{
{
Log
.
e
(
TAG
,
"onRunError Exception"
);
nativeDeviceException
(
userDataA
,
eA
.
getMessage
());
nativeDeviceException
(
userDataA
,
eA
.
getMessage
());
}
}
...
@@ -77,7 +79,6 @@ public class UsbDeviceJNI extends QtActivity
...
@@ -77,7 +79,6 @@ public class UsbDeviceJNI extends QtActivity
}
}
};
};
private
static
final
String
TAG
=
"QGC_UsbDeviceJNI"
;
// NATIVE C++ FUNCTION THAT WILL BE CALLED IF THE DEVICE IS UNPLUGGED
// NATIVE C++ FUNCTION THAT WILL BE CALLED IF THE DEVICE IS UNPLUGGED
private
static
native
void
nativeDeviceHasDisconnected
(
int
userDataA
);
private
static
native
void
nativeDeviceHasDisconnected
(
int
userDataA
);
...
@@ -120,7 +121,6 @@ public class UsbDeviceJNI extends QtActivity
...
@@ -120,7 +121,6 @@ public class UsbDeviceJNI extends QtActivity
return
true
;
return
true
;
}
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////////////////////////////
//
//
// List all available devices that are not already open. It returns the serial port info
// List all available devices that are not already open. It returns the serial port info
...
...
This diff is collapsed.
Click to expand it.
libs/qtandroidserialport/src/qserialport_android.cpp
View file @
6af9a170
...
@@ -54,8 +54,8 @@ QT_BEGIN_NAMESPACE
...
@@ -54,8 +54,8 @@ QT_BEGIN_NAMESPACE
#define BAD_PORT 0
#define BAD_PORT 0
static
const
char
V_j
niClassName
[]
{
"org/qgroundcontrol/qgchelper/UsbDeviceJNI"
};
static
const
char
kJ
niClassName
[]
{
"org/qgroundcontrol/qgchelper/UsbDeviceJNI"
};
static
const
char
V_TAG
[]
{
"QGC_QSerialPort"
};
static
const
char
kJTag
[]
{
"QGC_QSerialPort"
};
static
void
jniDeviceHasDisconnected
(
JNIEnv
*
envA
,
jobject
thizA
,
jint
userDataA
)
static
void
jniDeviceHasDisconnected
(
JNIEnv
*
envA
,
jobject
thizA
,
jint
userDataA
)
{
{
...
@@ -91,6 +91,15 @@ static void jniDeviceException(JNIEnv *envA, jobject thizA, jint userDataA, jstr
...
@@ -91,6 +91,15 @@ static void jniDeviceException(JNIEnv *envA, jobject thizA, jint userDataA, jstr
}
}
}
}
void
cleanJavaException
()
{
QAndroidJniEnvironment
env
;
if
(
env
->
ExceptionCheck
())
{
env
->
ExceptionDescribe
();
env
->
ExceptionClear
();
}
}
QSerialPortPrivate
::
QSerialPortPrivate
(
QSerialPort
*
q
)
QSerialPortPrivate
::
QSerialPortPrivate
(
QSerialPort
*
q
)
:
QSerialPortPrivateData
(
q
)
:
QSerialPortPrivateData
(
q
)
,
descriptor
(
-
1
)
,
descriptor
(
-
1
)
...
@@ -109,57 +118,75 @@ QSerialPortPrivate::QSerialPortPrivate(QSerialPort *q)
...
@@ -109,57 +118,75 @@ QSerialPortPrivate::QSerialPortPrivate(QSerialPort *q)
bool
QSerialPortPrivate
::
open
(
QIODevice
::
OpenMode
mode
)
bool
QSerialPortPrivate
::
open
(
QIODevice
::
OpenMode
mode
)
{
{
rwMode
=
mode
;
rwMode
=
mode
;
__android_log_print
(
ANDROID_LOG_INFO
,
V_TAG
,
"Opening %s"
,
systemLocation
.
toLatin1
().
data
());
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Opening %s"
,
systemLocation
.
toLatin1
().
data
());
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Calling Java Open"
);
QAndroidJniObject
jnameL
=
QAndroidJniObject
::
fromString
(
systemLocation
);
cleanJavaException
();
deviceId
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
kJniClassName
,
"open"
,
"(Ljava/lang/String;I)I"
,
jnameL
.
object
<
jstring
>
(),
(
jint
)
this
);
cleanJavaException
();
isReadStopped
=
false
;
if
(
deviceId
==
BAD_PORT
)
{
__android_log_print
(
ANDROID_LOG_ERROR
,
kJTag
,
"Error opening %s"
,
systemLocation
.
toLatin1
().
data
());
q_ptr
->
setError
(
QSerialPort
::
DeviceNotFoundError
);
return
false
;
}
if
(
!
hasRegisteredFunctions
)
if
(
!
hasRegisteredFunctions
)
{
{
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Registering Native Functions"
);
// REGISTER THE C++ FUNCTION WITH JNI
// REGISTER THE C++ FUNCTION WITH JNI
QAndroidJniEnvironment
envL
;
JNINativeMethod
javaMethods
[]
{
JNINativeMethod
methodsL
[]
{
{
"nativeDeviceHasDisconnected"
,
"(I)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceHasDisconnected
)},
{
"nativeDeviceHasDisconnected"
,
"(I)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceHasDisconnected
)},
{
"nativeDeviceNewData"
,
"(I[B)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceNewData
)},
{
"nativeDeviceNewData"
,
"(I[B)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceNewData
)},
{
"nativeDeviceException"
,
"(ILjava/lang/String;)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceException
)}
{
"nativeDeviceException"
,
"(ILjava/lang/String;)V"
,
reinterpret_cast
<
void
*>
(
jniDeviceException
)}
};
};
QAndroidJniObject
javaClassL
(
V_jniClassName
);
QAndroidJniEnvironment
jniEnv
;
jclass
objectClassL
=
envL
->
GetObjectClass
(
javaClassL
.
object
<
jobject
>
());
if
(
jniEnv
->
ExceptionCheck
())
{
jint
valL
=
envL
->
RegisterNatives
(
objectClassL
,
methodsL
,
sizeof
(
methodsL
)
/
sizeof
(
JNINativeMethod
));
jniEnv
->
ExceptionDescribe
();
envL
->
DeleteLocalRef
(
objectClassL
);
jniEnv
->
ExceptionClear
();
}
QAndroidJniObject
javaClass
(
kJniClassName
);
if
(
!
javaClass
.
isValid
())
{
__android_log_print
(
ANDROID_LOG_ERROR
,
kJTag
,
"Java class %s not valid"
,
kJniClassName
);
return
false
;
}
jclass
objectClass
=
jniEnv
->
GetObjectClass
(
javaClass
.
object
<
jobject
>
());
jint
val
=
jniEnv
->
RegisterNatives
(
objectClass
,
javaMethods
,
sizeof
(
javaMethods
)
/
sizeof
(
javaMethods
[
0
]));
jniEnv
->
DeleteLocalRef
(
objectClass
);
hasRegisteredFunctions
=
true
;
hasRegisteredFunctions
=
true
;
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Native Functions Registered"
);
if
(
envL
->
ExceptionCheck
())
if
(
jniEnv
->
ExceptionCheck
())
{
envL
->
ExceptionClear
();
jniEnv
->
ExceptionDescribe
();
jniEnv
->
ExceptionClear
();
}
if
(
val
L
<
0
)
{
if
(
val
<
0
)
{
__android_log_print
(
ANDROID_LOG_ERROR
,
V_TAG
,
"Error registering methods"
);
__android_log_print
(
ANDROID_LOG_ERROR
,
kJTag
,
"Error registering methods"
);
q_ptr
->
setError
(
QSerialPort
::
OpenError
);
q_ptr
->
setError
(
QSerialPort
::
OpenError
);
return
false
;
return
false
;
}
}
}
}
QAndroidJniObject
jnameL
=
QAndroidJniObject
::
fromString
(
systemLocation
);
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Calling Java getDeviceHandle"
);
deviceId
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
cleanJavaException
();
V_jniClassName
,
"open"
,
"(Ljava/lang/String;I)I"
,
jnameL
.
object
<
jstring
>
(),
(
jint
)
this
);
isReadStopped
=
false
;
if
(
deviceId
==
BAD_PORT
)
{
__android_log_print
(
ANDROID_LOG_ERROR
,
V_TAG
,
"Error opening %s"
,
systemLocation
.
toLatin1
().
data
());
q_ptr
->
setError
(
QSerialPort
::
DeviceNotFoundError
);
return
false
;
}
descriptor
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
descriptor
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
V_j
niClassName
,
kJ
niClassName
,
"getDeviceHandle"
,
"getDeviceHandle"
,
"(I)I"
,
"(I)I"
,
deviceId
);
deviceId
);
cleanJavaException
();
if
(
rwMode
==
QIODevice
::
WriteOnly
)
if
(
rwMode
==
QIODevice
::
WriteOnly
)
stopReadThread
();
stopReadThread
();
...
@@ -172,12 +199,14 @@ void QSerialPortPrivate::close()
...
@@ -172,12 +199,14 @@ void QSerialPortPrivate::close()
if
(
deviceId
==
BAD_PORT
)
if
(
deviceId
==
BAD_PORT
)
return
;
return
;
__android_log_print
(
ANDROID_LOG_INFO
,
V_TAG
,
"Closing %s"
,
systemLocation
.
toLatin1
().
data
());
__android_log_print
(
ANDROID_LOG_INFO
,
kJTag
,
"Closing %s"
,
systemLocation
.
toLatin1
().
data
());
cleanJavaException
();
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_j
niClassName
,
kJ
niClassName
,
"close"
,
"close"
,
"(I)Z"
,
"(I)Z"
,
deviceId
);
deviceId
);
cleanJavaException
();
descriptor
=
-
1
;
descriptor
=
-
1
;
isCustomBaudRateSupported
=
false
;
isCustomBaudRateSupported
=
false
;
...
@@ -196,14 +225,17 @@ bool QSerialPortPrivate::setParameters(int baudRateA, int dataBitsA, int stopBit
...
@@ -196,14 +225,17 @@ bool QSerialPortPrivate::setParameters(int baudRateA, int dataBitsA, int stopBit
return
false
;
return
false
;
}
}
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
cleanJavaException
();
"setParameters"
,
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
"(IIIII)Z"
,
kJniClassName
,
deviceId
,
"setParameters"
,
baudRateA
,
"(IIIII)Z"
,
dataBitsA
,
deviceId
,
stopBitsA
,
baudRateA
,
parityA
);
dataBitsA
,
stopBitsA
,
parityA
);
cleanJavaException
();
if
(
resultL
)
if
(
resultL
)
{
{
...
@@ -223,11 +255,13 @@ void QSerialPortPrivate::stopReadThread()
...
@@ -223,11 +255,13 @@ void QSerialPortPrivate::stopReadThread()
{
{
if
(
isReadStopped
)
if
(
isReadStopped
)
return
;
return
;
cleanJavaException
();
QAndroidJniObject
::
callStaticMethod
<
void
>
(
V_jniClassName
,
QAndroidJniObject
::
callStaticMethod
<
void
>
(
"stopIoManager"
,
kJniClassName
,
"(I)V"
,
"stopIoManager"
,
deviceId
);
"(I)V"
,
deviceId
);
cleanJavaException
();
isReadStopped
=
true
;
isReadStopped
=
true
;
}
}
...
@@ -237,26 +271,21 @@ void QSerialPortPrivate::startReadThread()
...
@@ -237,26 +271,21 @@ void QSerialPortPrivate::startReadThread()
{
{
if
(
!
isReadStopped
)
if
(
!
isReadStopped
)
return
;
return
;
cleanJavaException
();
QAndroidJniObject
::
callStaticMethod
<
void
>
(
V_jniClassName
,
QAndroidJniObject
::
callStaticMethod
<
void
>
(
"startIoManager"
,
kJniClassName
,
"(I)V"
,
"startIoManager"
,
deviceId
);
"(I)V"
,
deviceId
);
cleanJavaException
();
isReadStopped
=
false
;
isReadStopped
=
false
;
}
}
QSerialPort
::
PinoutSignals
QSerialPortPrivate
::
pinoutSignals
()
QSerialPort
::
PinoutSignals
QSerialPortPrivate
::
pinoutSignals
()
{
{
return
QSerialPort
::
NoSignal
;
return
QSerialPort
::
NoSignal
;
}
}
bool
QSerialPortPrivate
::
setDataTerminalReady
(
bool
set
)
bool
QSerialPortPrivate
::
setDataTerminalReady
(
bool
set
)
{
{
if
(
deviceId
==
BAD_PORT
)
if
(
deviceId
==
BAD_PORT
)
...
@@ -264,17 +293,17 @@ bool QSerialPortPrivate::setDataTerminalReady(bool set)
...
@@ -264,17 +293,17 @@ bool QSerialPortPrivate::setDataTerminalReady(bool set)
q_ptr
->
setError
(
QSerialPort
::
NotOpenError
);
q_ptr
->
setError
(
QSerialPort
::
NotOpenError
);
return
false
;
return
false
;
}
}
cleanJavaException
();
return
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
bool
res
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
"setDataTerminalReady"
,
kJniClassName
,
"(IZ)Z"
,
"setDataTerminalReady"
,
deviceId
,
"(IZ)Z"
,
set
);
deviceId
,
set
);
cleanJavaException
();
return
res
;
}
}
bool
QSerialPortPrivate
::
setRequestToSend
(
bool
set
)
bool
QSerialPortPrivate
::
setRequestToSend
(
bool
set
)
{
{
if
(
deviceId
==
BAD_PORT
)
if
(
deviceId
==
BAD_PORT
)
...
@@ -282,25 +311,22 @@ bool QSerialPortPrivate::setRequestToSend(bool set)
...
@@ -282,25 +311,22 @@ bool QSerialPortPrivate::setRequestToSend(bool set)
q_ptr
->
setError
(
QSerialPort
::
NotOpenError
);
q_ptr
->
setError
(
QSerialPort
::
NotOpenError
);
return
false
;
return
false
;
}
}
cleanJavaException
();
return
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
bool
res
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
"setRequestToSend"
,
kJniClassName
,
"(IZ)Z"
,
"setRequestToSend"
,
deviceId
,
"(IZ)Z"
,
set
);
deviceId
,
set
);
cleanJavaException
();
return
res
;
}
}
bool
QSerialPortPrivate
::
flush
()
bool
QSerialPortPrivate
::
flush
()
{
{
return
writeDataOneShot
();
return
writeDataOneShot
();
}
}
bool
QSerialPortPrivate
::
clear
(
QSerialPort
::
Directions
directions
)
bool
QSerialPortPrivate
::
clear
(
QSerialPort
::
Directions
directions
)
{
{
if
(
deviceId
==
BAD_PORT
)
if
(
deviceId
==
BAD_PORT
)
...
@@ -323,16 +349,18 @@ bool QSerialPortPrivate::clear(QSerialPort::Directions directions)
...
@@ -323,16 +349,18 @@ bool QSerialPortPrivate::clear(QSerialPort::Directions directions)
outputL
=
true
;
outputL
=
true
;
}
}
return
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
cleanJavaException
();
"purgeBuffers"
,
bool
res
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
"(IZZ)Z"
,
kJniClassName
,
deviceId
,
"purgeBuffers"
,
inputL
,
"(IZZ)Z"
,
outputL
);
deviceId
,
}
inputL
,
outputL
);
cleanJavaException
();
return
res
;
}
bool
QSerialPortPrivate
::
sendBreak
(
int
duration
)
bool
QSerialPortPrivate
::
sendBreak
(
int
duration
)
{
{
...
@@ -340,26 +368,17 @@ bool QSerialPortPrivate::sendBreak(int duration)
...
@@ -340,26 +368,17 @@ bool QSerialPortPrivate::sendBreak(int duration)
return
true
;
return
true
;
}
}
bool
QSerialPortPrivate
::
setBreakEnabled
(
bool
set
)
bool
QSerialPortPrivate
::
setBreakEnabled
(
bool
set
)
{
{
Q_UNUSED
(
set
);
Q_UNUSED
(
set
);
return
true
;
return
true
;
}
}
void
QSerialPortPrivate
::
startWriting
()
void
QSerialPortPrivate
::
startWriting
()
{
{
writeDataOneShot
();
writeDataOneShot
();
}
}
bool
QSerialPortPrivate
::
waitForReadyRead
(
int
msecs
)
bool
QSerialPortPrivate
::
waitForReadyRead
(
int
msecs
)
{
{
int
origL
=
readBuffer
.
size
();
int
origL
=
readBuffer
.
size
();
...
@@ -378,41 +397,26 @@ bool QSerialPortPrivate::waitForReadyRead(int msecs)
...
@@ -378,41 +397,26 @@ bool QSerialPortPrivate::waitForReadyRead(int msecs)
return
false
;
return
false
;
}
}
bool
QSerialPortPrivate
::
waitForBytesWritten
(
int
msecs
)
bool
QSerialPortPrivate
::
waitForBytesWritten
(
int
msecs
)
{
{
internalWriteTimeoutMsec
=
msecs
;
internalWriteTimeoutMsec
=
msecs
;
bool
retL
=
writeDataOneShot
();
bool
retL
=
writeDataOneShot
();
internalWriteTimeoutMsec
=
0
;
internalWriteTimeoutMsec
=
0
;
return
retL
;
return
retL
;
}
}
bool
QSerialPortPrivate
::
setBaudRate
()
bool
QSerialPortPrivate
::
setBaudRate
()
{
{
setBaudRate
(
inputBaudRate
,
QSerialPort
::
AllDirections
);
setBaudRate
(
inputBaudRate
,
QSerialPort
::
AllDirections
);
return
true
;
return
true
;
}
}
bool
QSerialPortPrivate
::
setBaudRate
(
qint32
baudRate
,
QSerialPort
::
Directions
directions
)
bool
QSerialPortPrivate
::
setBaudRate
(
qint32
baudRate
,
QSerialPort
::
Directions
directions
)
{
{
Q_UNUSED
(
directions
);
Q_UNUSED
(
directions
);
return
setParameters
(
baudRate
,
jniDataBits
,
jniStopBits
,
jniParity
);
return
setParameters
(
baudRate
,
jniDataBits
,
jniStopBits
,
jniParity
);
}
}
bool
QSerialPortPrivate
::
setDataBits
(
QSerialPort
::
DataBits
dataBits
)
bool
QSerialPortPrivate
::
setDataBits
(
QSerialPort
::
DataBits
dataBits
)
{
{
int
numBitsL
=
8
;
int
numBitsL
=
8
;
...
@@ -436,17 +440,12 @@ bool QSerialPortPrivate::setDataBits(QSerialPort::DataBits dataBits)
...
@@ -436,17 +440,12 @@ bool QSerialPortPrivate::setDataBits(QSerialPort::DataBits dataBits)
numBitsL
=
8
;
numBitsL
=
8
;
break
;
break
;
}
}
return
setParameters
(
inputBaudRate
,
numBitsL
,
jniStopBits
,
jniParity
);
return
setParameters
(
inputBaudRate
,
numBitsL
,
jniStopBits
,
jniParity
);
}
}
bool
QSerialPortPrivate
::
setParity
(
QSerialPort
::
Parity
parity
)
bool
QSerialPortPrivate
::
setParity
(
QSerialPort
::
Parity
parity
)
{
{
int
parL
=
0
;
int
parL
=
0
;
switch
(
parity
)
switch
(
parity
)
{
{
case
QSerialPort
:
:
SpaceParity
:
case
QSerialPort
:
:
SpaceParity
:
...
@@ -470,17 +469,12 @@ bool QSerialPortPrivate::setParity(QSerialPort::Parity parity)
...
@@ -470,17 +469,12 @@ bool QSerialPortPrivate::setParity(QSerialPort::Parity parity)
parL
=
0
;
parL
=
0
;
break
;
break
;
}
}
return
setParameters
(
inputBaudRate
,
jniDataBits
,
jniStopBits
,
parL
);
return
setParameters
(
inputBaudRate
,
jniDataBits
,
jniStopBits
,
parL
);
}
}
bool
QSerialPortPrivate
::
setStopBits
(
QSerialPort
::
StopBits
stopBits
)
bool
QSerialPortPrivate
::
setStopBits
(
QSerialPort
::
StopBits
stopBits
)
{
{
int
stopL
=
1
;
int
stopL
=
1
;
switch
(
stopBits
)
switch
(
stopBits
)
{
{
case
QSerialPort
:
:
TwoStop
:
case
QSerialPort
:
:
TwoStop
:
...
@@ -496,29 +490,21 @@ bool QSerialPortPrivate::setStopBits(QSerialPort::StopBits stopBits)
...
@@ -496,29 +490,21 @@ bool QSerialPortPrivate::setStopBits(QSerialPort::StopBits stopBits)
stopL
=
1
;
stopL
=
1
;
break
;
break
;
}
}
return
setParameters
(
inputBaudRate
,
jniDataBits
,
stopL
,
jniParity
);
return
setParameters
(
inputBaudRate
,
jniDataBits
,
stopL
,
jniParity
);
}
}
bool
QSerialPortPrivate
::
setFlowControl
(
QSerialPort
::
FlowControl
flowControl
)
bool
QSerialPortPrivate
::
setFlowControl
(
QSerialPort
::
FlowControl
flowControl
)
{
{
Q_UNUSED
(
flowControl
);
Q_UNUSED
(
flowControl
);
return
true
;
return
true
;
}
}
bool
QSerialPortPrivate
::
setDataErrorPolicy
(
QSerialPort
::
DataErrorPolicy
policy
)
bool
QSerialPortPrivate
::
setDataErrorPolicy
(
QSerialPort
::
DataErrorPolicy
policy
)
{
{
this
->
policy
=
policy
;
this
->
policy
=
policy
;
return
true
;
return
true
;
}
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void
QSerialPortPrivate
::
newDataArrived
(
char
*
bytesA
,
int
lengthA
)
void
QSerialPortPrivate
::
newDataArrived
(
char
*
bytesA
,
int
lengthA
)
{
{
...
@@ -550,8 +536,6 @@ void QSerialPortPrivate::exceptionArrived(QString strA)
...
@@ -550,8 +536,6 @@ void QSerialPortPrivate::exceptionArrived(QString strA)
q_ptr
->
setErrorString
(
strA
);
q_ptr
->
setErrorString
(
strA
);
}
}
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////
bool
QSerialPortPrivate
::
writeDataOneShot
()
bool
QSerialPortPrivate
::
writeDataOneShot
()
{
{
...
@@ -580,8 +564,6 @@ bool QSerialPortPrivate::writeDataOneShot()
...
@@ -580,8 +564,6 @@ bool QSerialPortPrivate::writeDataOneShot()
return
(
pendingBytesWritten
<
0
)
?
false
:
true
;
return
(
pendingBytesWritten
<
0
)
?
false
:
true
;
}
}
QSerialPort
::
SerialPortError
QSerialPortPrivate
::
decodeSystemError
()
const
QSerialPort
::
SerialPortError
QSerialPortPrivate
::
decodeSystemError
()
const
{
{
QSerialPort
::
SerialPortError
error
;
QSerialPort
::
SerialPortError
error
;
...
@@ -611,8 +593,6 @@ QSerialPort::SerialPortError QSerialPortPrivate::decodeSystemError() const
...
@@ -611,8 +593,6 @@ QSerialPort::SerialPortError QSerialPortPrivate::decodeSystemError() const
return
error
;
return
error
;
}
}
////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////
qint64
QSerialPortPrivate
::
writeToPort
(
const
char
*
data
,
qint64
maxSize
)
qint64
QSerialPortPrivate
::
writeToPort
(
const
char
*
data
,
qint64
maxSize
)
{
{
...
@@ -622,32 +602,30 @@ qint64 QSerialPortPrivate::writeToPort(const char *data, qint64 maxSize)
...
@@ -622,32 +602,30 @@ qint64 QSerialPortPrivate::writeToPort(const char *data, qint64 maxSize)
return
0
;
return
0
;
}
}
QAndroidJniEnvironment
envL
;
QAndroidJniEnvironment
jniEnv
;
jbyteArray
jarrayL
=
envL
->
NewByteArray
(
maxSize
);
jbyteArray
jarrayL
=
jniEnv
->
NewByteArray
(
maxSize
);
envL
->
SetByteArrayRegion
(
jarrayL
,
0
,
maxSize
,
(
jbyte
*
)
data
);
jniEnv
->
SetByteArrayRegion
(
jarrayL
,
0
,
maxSize
,
(
jbyte
*
)
data
);
int
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
V_jniClassName
,
if
(
jniEnv
->
ExceptionCheck
())
"write"
,
jniEnv
->
ExceptionClear
();
"(I[BI)I"
,
int
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jint
>
(
deviceId
,
kJniClassName
,
jarrayL
,
"write"
,
internalWriteTimeoutMsec
);
"(I[BI)I"
,
deviceId
,
if
(
envL
->
ExceptionCheck
())
jarrayL
,
internalWriteTimeoutMsec
);
if
(
jniEnv
->
ExceptionCheck
())
{
{
envL
->
ExceptionClear
();
jniEnv
->
ExceptionClear
();
q_ptr
->
setErrorString
(
QStringLiteral
(
"Writing to the device threw an exception"
));
q_ptr
->
setErrorString
(
QStringLiteral
(
"Writing to the device threw an exception"
));
envL
->
DeleteLocalRef
(
jarrayL
);
jniEnv
->
DeleteLocalRef
(
jarrayL
);
return
0
;
return
0
;
}
}
jniEnv
->
DeleteLocalRef
(
jarrayL
);
envL
->
DeleteLocalRef
(
jarrayL
);
return
resultL
;
return
resultL
;
}
}
static
inline
bool
evenParity
(
quint8
c
)
static
inline
bool
evenParity
(
quint8
c
)
{
{
c
^=
c
>>
4
;
//(c7 ^ c3)(c6 ^ c2)(c5 ^ c1)(c4 ^ c0)
c
^=
c
>>
4
;
//(c7 ^ c3)(c6 ^ c2)(c5 ^ c1)(c4 ^ c0)
...
@@ -803,42 +781,27 @@ static const BaudRateMap createStandardBaudRateMap()
...
@@ -803,42 +781,27 @@ static const BaudRateMap createStandardBaudRateMap()
return
baudRateMap
;
return
baudRateMap
;
}
}
static
const
BaudRateMap
&
standardBaudRateMap
()
static
const
BaudRateMap
&
standardBaudRateMap
()
{
{
static
const
BaudRateMap
baudRateMap
=
createStandardBaudRateMap
();
static
const
BaudRateMap
baudRateMap
=
createStandardBaudRateMap
();
return
baudRateMap
;
return
baudRateMap
;
}
}
qint32
QSerialPortPrivate
::
baudRateFromSetting
(
qint32
setting
)
qint32
QSerialPortPrivate
::
baudRateFromSetting
(
qint32
setting
)
{
{
return
standardBaudRateMap
().
key
(
setting
);
return
standardBaudRateMap
().
key
(
setting
);
}
}
qint32
QSerialPortPrivate
::
settingFromBaudRate
(
qint32
baudRate
)
qint32
QSerialPortPrivate
::
settingFromBaudRate
(
qint32
baudRate
)
{
{
return
standardBaudRateMap
().
value
(
baudRate
);
return
standardBaudRateMap
().
value
(
baudRate
);
}
}
QList
<
qint32
>
QSerialPortPrivate
::
standardBaudRates
()
QList
<
qint32
>
QSerialPortPrivate
::
standardBaudRates
()
{
{
return
standardBaudRateMap
().
keys
();
return
standardBaudRateMap
().
keys
();
}
}
QSerialPort
::
Handle
QSerialPort
::
handle
()
const
QSerialPort
::
Handle
QSerialPort
::
handle
()
const
{
{
Q_D
(
const
QSerialPort
);
Q_D
(
const
QSerialPort
);
...
...
This diff is collapsed.
Click to expand it.
libs/qtandroidserialport/src/qserialportinfo_android.cpp
View file @
6af9a170
...
@@ -48,6 +48,8 @@ QT_BEGIN_NAMESPACE
...
@@ -48,6 +48,8 @@ QT_BEGIN_NAMESPACE
static
const
char
V_jniClassName
[]
{
"org/qgroundcontrol/qgchelper/UsbDeviceJNI"
};
static
const
char
V_jniClassName
[]
{
"org/qgroundcontrol/qgchelper/UsbDeviceJNI"
};
static
const
char
V_TAG
[]
{
"QGC_QSerialPortInfo"
};
static
const
char
V_TAG
[]
{
"QGC_QSerialPortInfo"
};
extern
void
cleanJavaException
();
QList
<
QSerialPortInfo
>
availablePortsByFiltersOfDevices
(
bool
&
ok
)
QList
<
QSerialPortInfo
>
availablePortsByFiltersOfDevices
(
bool
&
ok
)
{
{
QList
<
QSerialPortInfo
>
serialPortInfoList
;
QList
<
QSerialPortInfo
>
serialPortInfoList
;
...
@@ -117,22 +119,26 @@ QList<qint32> QSerialPortInfo::standardBaudRates()
...
@@ -117,22 +119,26 @@ QList<qint32> QSerialPortInfo::standardBaudRates()
bool
QSerialPortInfo
::
isBusy
()
const
bool
QSerialPortInfo
::
isBusy
()
const
{
{
QAndroidJniObject
jstrL
=
QAndroidJniObject
::
fromString
(
d_ptr
->
portName
);
QAndroidJniObject
jstrL
=
QAndroidJniObject
::
fromString
(
d_ptr
->
portName
);
cleanJavaException
();
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
V_jniClassName
,
"isDeviceNameOpen"
,
"isDeviceNameOpen"
,
"(Ljava/lang/String;)Z"
,
"(Ljava/lang/String;)Z"
,
jstrL
.
object
<
jstring
>
());
jstrL
.
object
<
jstring
>
());
cleanJavaException
();
return
resultL
;
return
resultL
;
}
}
bool
QSerialPortInfo
::
isValid
()
const
bool
QSerialPortInfo
::
isValid
()
const
{
{
QAndroidJniObject
jstrL
=
QAndroidJniObject
::
fromString
(
d_ptr
->
portName
);
QAndroidJniObject
jstrL
=
QAndroidJniObject
::
fromString
(
d_ptr
->
portName
);
cleanJavaException
();
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
jboolean
resultL
=
QAndroidJniObject
::
callStaticMethod
<
jboolean
>
(
V_jniClassName
,
V_jniClassName
,
"isDeviceNameValid"
,
"isDeviceNameValid"
,
"(Ljava/lang/String;)Z"
,
"(Ljava/lang/String;)Z"
,
jstrL
.
object
<
jstring
>
());
jstrL
.
object
<
jstring
>
());
cleanJavaException
();
return
resultL
;
return
resultL
;
}
}
...
...
This diff is collapsed.
Click to expand it.
src/QGCApplication.cc
View file @
6af9a170
...
@@ -104,7 +104,9 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
...
@@ -104,7 +104,9 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) :
_app
=
this
;
_app
=
this
;
// This prevents usage of QQuickWidget to fail since it doesn't support native widget siblings
// This prevents usage of QQuickWidget to fail since it doesn't support native widget siblings
#ifndef __android__
setAttribute
(
Qt
::
AA_DontCreateNativeWidgetSiblings
);
setAttribute
(
Qt
::
AA_DontCreateNativeWidgetSiblings
);
#endif
#ifdef QT_DEBUG
#ifdef QT_DEBUG
// First thing we want to do is set up the qtlogging.ini file. If it doesn't already exist we copy
// First thing we want to do is set up the qtlogging.ini file. If it doesn't already exist we copy
...
...
This diff is collapsed.
Click to expand it.
src/QGCFileDialog.cc
View file @
6af9a170
...
@@ -217,10 +217,10 @@ void QGCFileDialog::_validate(Options& options)
...
@@ -217,10 +217,10 @@ void QGCFileDialog::_validate(Options& options)
Q_ASSERT
(
qgcApp
());
Q_ASSERT
(
qgcApp
());
Q_ASSERT_X
(
QThread
::
currentThread
()
==
qgcApp
()
->
thread
(),
"Threading issue"
,
"QGCFileDialog can only be called from main thread"
);
Q_ASSERT_X
(
QThread
::
currentThread
()
==
qgcApp
()
->
thread
(),
"Threading issue"
,
"QGCFileDialog can only be called from main thread"
);
#ifndef __android__
// On OSX native dialog can hang so we always use Qt dialogs
// On OSX native dialog can hang so we always use Qt dialogs
options
|=
DontUseNativeDialog
;
options
|=
DontUseNativeDialog
;
#endif
if
(
MainWindow
::
instance
())
{
if
(
MainWindow
::
instance
())
{
MainWindow
::
instance
()
->
hideSplashScreen
();
MainWindow
::
instance
()
->
hideSplashScreen
();
}
}
...
...
This diff is collapsed.
Click to expand it.
src/ui/MainWindow.cc
View file @
6af9a170
...
@@ -183,8 +183,10 @@ MainWindow::MainWindow(QSplashScreen* splashScreen)
...
@@ -183,8 +183,10 @@ MainWindow::MainWindow(QSplashScreen* splashScreen)
// Qt 4 on Ubuntu does place the native menubar correctly so on Linux we revert back to in-window menu bar.
// Qt 4 on Ubuntu does place the native menubar correctly so on Linux we revert back to in-window menu bar.
// TODO: Check that this is still necessary on Qt5 on Ubuntu
// TODO: Check that this is still necessary on Qt5 on Ubuntu
#ifdef Q_OS_LINUX
#ifdef Q_OS_LINUX
#ifndef __android__
menuBar
()
->
setNativeMenuBar
(
false
);
menuBar
()
->
setNativeMenuBar
(
false
);
#endif
#endif
#endif
#ifdef UNITTEST_BUILD
#ifdef UNITTEST_BUILD
QAction
*
qmlTestAction
=
new
QAction
(
"Test QML palette and controls"
,
NULL
);
QAction
*
qmlTestAction
=
new
QAction
(
"Test QML palette and controls"
,
NULL
);
...
...
This diff is collapsed.
Click to expand it.
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