QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
AndroidSerial.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QByteArray>
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QString>
6#include <qserialport.h>
7#include <qserialportinfo.h>
8
9Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog);
10
12
13namespace AndroidSerial {
15{
16 Data5 = 5,
17 Data6 = 6,
18 Data7 = 7,
19 Data8 = 8
20};
21
30
32{
35 TwoStop = 2
36};
37
47
56
57constexpr char CHAR_XON = 17;
58constexpr char CHAR_XOFF = 19;
59
60constexpr const char* kJniUsbSerialManagerClassName = "org/mavlink/qgroundcontrol/QGCUsbSerialManager";
61
62void setNativeMethods();
63QList<QSerialPortInfo> availableDevices();
64int getDeviceId(const QString& portName);
65int getDeviceHandle(int deviceId);
66int open(const QString& portName, QSerialPortPrivate* classPtr);
67bool close(int deviceId);
68bool isOpen(const QString& portName);
69QByteArray read(int deviceId, int length, int timeout);
70int write(int deviceId, const char* data, int length, int timeout, bool async);
71bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity);
72bool getCarrierDetect(int deviceId);
73bool getClearToSend(int deviceId);
74bool getDataSetReady(int deviceId);
75bool getDataTerminalReady(int deviceId);
76bool setDataTerminalReady(int deviceId, bool set);
77bool getRingIndicator(int deviceId);
78bool getRequestToSend(int deviceId);
79bool setRequestToSend(int deviceId, bool set);
80QSerialPort::PinoutSignals getControlLines(int deviceId);
81int getFlowControl(int deviceId);
82bool setFlowControl(int deviceId, int flowControl);
83bool purgeBuffers(int deviceId, bool input, bool output);
84bool setBreak(int deviceId, bool set);
85bool startReadThread(int deviceId);
86bool stopReadThread(int deviceId);
87bool readThreadRunning(int deviceId);
88
91void cleanupJniCache();
92} // namespace AndroidSerial
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
int open(const QString &portName, QSerialPortPrivate *classPtr)
bool getRingIndicator(int deviceId)
void registerPointer(QSerialPortPrivate *ptr)
QByteArray read(int deviceId, int length, int timeout)
int getDeviceHandle(int deviceId)
QList< QSerialPortInfo > availableDevices()
bool getRequestToSend(int deviceId)
bool getDataTerminalReady(int deviceId)
constexpr const char * kJniUsbSerialManagerClassName
void unregisterPointer(QSerialPortPrivate *ptr)
int getDeviceId(const QString &portName)
bool setDataTerminalReady(int deviceId, bool set)
void setNativeMethods()
int write(int deviceId, const char *data, int length, int timeout, bool async)
bool setParameters(int deviceId, int baudRate, int dataBits, int stopBits, int parity)
bool startReadThread(int deviceId)
int getFlowControl(int deviceId)
QSerialPort::PinoutSignals getControlLines(int deviceId)
bool getDataSetReady(int deviceId)
bool setRequestToSend(int deviceId, bool set)
bool getClearToSend(int deviceId)
bool purgeBuffers(int deviceId, bool input, bool output)
bool getCarrierDetect(int deviceId)
bool isOpen(const QString &portName)
bool readThreadRunning(int deviceId)
bool close(int deviceId)
bool stopReadThread(int deviceId)
constexpr char CHAR_XON
bool setFlowControl(int deviceId, int flowControl)
constexpr char CHAR_XOFF
bool setBreak(int deviceId, bool set)