dfti::Autopilot Class Reference
Serial driver to acquire data from a MAVLink-based autopilot. More...
#include <autopilot.hh>
Inheritance diagram for dfti::Autopilot:

Collaboration diagram for dfti::Autopilot:

Public Slots | |
void | readData (void) |
Slot to read in data over serial and parse complete packets. | |
![]() | |
virtual void | readData (void)=0 |
Slot to read in data over serial and parse complete packets. | |
Signals | |
void | measurementUpdate (APData data) |
Emitted to share new APData. | |
Public Member Functions | |
Autopilot (Settings *_settings, QObject *_parent=nullptr) | |
Constructor. More... | |
void | open (void) |
Opens the serial port. More... | |
void | requestStream (quint8 streamId, quint16 streamRate, quint8 enabled) |
Request a MAVLink message at a given rate. More... | |
void | getDataRate (quint16 msgId) |
Request current MAVLink message data rate. More... | |
void | setDataRate (quint8 msgId, float msgRate) |
Request a MAVLink message at a given rate. More... | |
![]() | |
SerialSensor (Settings *_settings, QObject *_parent=nullptr) | |
Constructor. More... | |
~SerialSensor () | |
Destructor. | |
void | configureSerial (QString _portName) |
Set the serial port parameters. More... | |
void | init () |
Initialize the serial port. | |
bool | isOpen (void) |
Returns true if the serial port is open. More... | |
void | setBaudRate (quint32 rate) |
Set the serial port baud rate. More... | |
void | threadStart (void) |
Start the sensor in a thread. | |
Additional Inherited Members | |
![]() | |
QString | validateSerialPort (QString _port) |
Validates a proposed serial port. More... | |
![]() | |
QPointer< Settings > | settings = nullptr |
Settings object. | |
QString | portName {""} |
Serial port name. | |
QSerialPort::BaudRate | baudRate {QSerialPort::Baud115200} |
Serial port baud rate. | |
bool | _valid_serial = false |
Indicates if serial port passed validation. | |
QPointer< QSerialPort > | _port = nullptr |
Serial port object. | |
Detailed Description
Serial driver to acquire data from a MAVLink-based autopilot.
Constructor & Destructor Documentation
|
explicit |
Constructor.
- Parameters
-
_settings Pointer to Settings object. _parent Pointer to parent QObject.
Member Function Documentation
void dfti::Autopilot::getDataRate | ( | quint16 | msgId | ) |
Request current MAVLink message data rate.
- Remarks
- See http://mavlink.org/messages/common for MAVLink message info. Note also that this should return a MESSAGE_INTERVAL message, so you should make sure this message is handled.
- Parameters
-
msgId The MAVLink message ID.
|
virtual |
Opens the serial port.
Overrides the SerialSensor::open method to open the serial port as R/W.
Reimplemented from dfti::SerialSensor.
void dfti::Autopilot::requestStream | ( | quint8 | streamId, |
quint16 | streamRate, | ||
quint8 | enabled | ||
) |
Request a MAVLink message at a given rate.
- Deprecated:
- REQUEST_DATA_STREAM is deprecated in favor of the MESSAGE_INTERVAL MAVLink message. However, at this time APM does not support this latter interface.
- Remarks
- See http://mavlink.org/messages/common for the MAVLink MAV_DATA_STREAM enum.
- Parameters
-
streamId The MAVLink stream ID. streamRate Requested rate of the stream in Hz. enabled Use 1 to enable the stream and 0 to disabled.
void dfti::Autopilot::setDataRate | ( | quint8 | msgId, |
float | msgRate | ||
) |
Request a MAVLink message at a given rate.
- Remarks
- See http://mavlink.org/messages/common for MAVLink message info.
- Parameters
-
msgId The MAVLink message ID. msgRate Requested rate of the message in microseconds. To disable output, use -1, and to reset to the default rate, use 0.
The documentation for this class was generated from the following files: