Currently when adding a hostname in string form for tcp connection,
resolving to IP is done immediately, and in case of an error
the host is not stored and used default one instead.
Also the ip might be not known when adding the config, but hostname is known,
which also might be not resolvable at time when the config is being created.
Since hostName in QAbstractSocket::connectToHost
may be an IP address in string form (e.g., "43.195.83.32"),
or it may be a host name (e.g., "example.com").
QAbstractSocket will do a lookup only if required.
So suggesting to totally remove resolving of ip from TCPLink.
Resolving will be performed in QTcpSocket::connectToHost() when actual connection is requested.
* Remove the `LinkInterface::Channel` object
* Remove the reserved channel 0 and make channel 0 reservable
* Ensure that any user of the `reserveMavlinkChannel()` function will get a compiler error to note that a return of 0 no longer means error
* Make the `APMFirmwarePlugin` use a static channel member mutexed also by a static member
* `_handleIncomingMavlinkBytes` needs to use a different channel because it processes messages parallel to `MAVLinkProtocol::receiveBytes`
* `_handleIncomingMavlinkBytes`'s auxiliary channel needs its own mutex guard
* LinkManager::createConnectedLink: use make_shared to avoid separate allocation
Also avoids some memory leaks when returning early.
* fix LinkManager: set setAutoConnect()
* fix MAVLinkProtocol: use a weak_ptr to check if the link stays valid
It is not enough to check if the link is valid only on entering the method.
If message handling called VehicleLinkManager::closeVehicle(), the link
was removed, and possibly deleted. If more mavlink messages were in the
same buffer, the link was accessed again, triggering a segfault.
This happened for example when rebooting the vehicle from parameter editor.
* Vehicle: fix uninitialized variable _capabilityBits
From valgrind:
==690288== Conditional jump or move depends on uninitialised value(s)
==690288== at 0x5B5F18: GeoFenceController::supported() const (GeoFenceController.cc:495)
==690288== by 0x5B309E: GeoFenceController::_managerVehicleChanged(Vehicle*) (GeoFenceController.cc:125)
==690288== by 0x5B79AF: QtPrivate::FunctorCall<QtPrivate::IndexesList<0>, QtPrivate::List<Vehicle*>, void, void (GeoFenceController::*)(Vehicle*)>::call(void (GeoFenceController::*)(Vehicle*), GeoFenceController*, void**) (qobjectdefs_impl.h:152)
==690288== by 0x5B7797: void QtPrivate::FunctionPointer<void (GeoFenceController::*)(Vehicle*)>::call<QtPrivate::List<Vehicle*>, void>(void (GeoFenceController::*)(Vehicle*), GeoFenceController*, void**) (qobjectdefs_impl.h:185)
==690288== by 0x5B7325: QtPrivate::QSlotObject<void (GeoFenceController::*)(Vehicle*), QtPrivate::List<Vehicle*>, void>::impl(int, QtPrivate::QSlotObjectBase*, QObject*, void**, bool*) (qobjectdefs_impl.h:414)
==690288== by 0x9D43DF5: QMetaObject::activate(QObject*, int, int, void**) (in /opt/install/qt/5.12.5/gcc_64/lib/libQt5Core.so.5.12.5)
==690288== by 0x913C9C: PlanMasterController::managerVehicleChanged(Vehicle*) (moc_PlanMasterController.cpp:544)
==690288== by 0x5FF00B: PlanMasterController::_activeVehicleChanged(Vehicle*) (PlanMasterController.cc:160)
==690288== by 0x5FE9A4: PlanMasterController::startStaticActiveVehicle(Vehicle*, bool) (PlanMasterController.cc:116)
==690288== by 0x912EB9: PlanMasterController::qt_static_metacall(QObject*, QMetaObject::Call, int, void**) (moc_PlanMasterController.cpp:267)
==690288== by 0x913A2A: PlanMasterController::qt_metacall(QMetaObject::Call, int, void**) (moc_PlanMasterController.cpp:473)
==690288== by 0x880E5C8: QQmlObjectOrGadget::metacall(QMetaObject::Call, int, void**) const (in /opt/install/qt/5.12.5/gcc_64/lib/libQt5Qml.so.5.12.5)
* FTPManager: fix uninitialized variable & message filter logic
From Valgrind:
==690288== Conditional jump or move depends on uninitialised value(s)
==690288== at 0x6E74E6: FTPManager::_mavlinkMessageReceived(__mavlink_message const&) (FTPManager.cc:108)
==690288== by 0x70D164: Vehicle::_mavlinkMessageReceived(LinkInterface*, __mavlink_message) (Vehicle.cc:603)
==690288== by 0x726F53: QtPrivate::FunctorCall<QtPrivate::IndexesList<0, 1>, QtPrivate::List<LinkInterface*, __mavlink_message>, void, void (Vehicle::*)(LinkInterface*, __mavlink_message)>::call(void (Vehicle::*)(LinkInterface*, __mavlink_message), Vehicle*, void**) (qobjectdefs_impl.h:152)
==690288== by 0x725990: void QtPrivate::FunctionPointer<void (Vehicle::*)(LinkInterface*, __mavlink_message)>::call<QtPrivate::List<LinkInterface*, __mavlink_message>, void>(void (Vehicle::*)(LinkInterface*, __mavlink_message), Vehicle*, void**) (qobjectdefs_impl.h:185)
==690288== by 0x723B4B: QtPrivate::QSlotObject<void (Vehicle::*)(LinkInterface*, __mavlink_message), QtPrivate::List<LinkInterface*, __mavlink_message>, void>::impl(int, QtPrivate::QSlotObjectBase*, QObject*, void**, bool*) (qobjectdefs_impl.h:414)
==690288== by 0x9D43DF5: QMetaObject::activate(QObject*, int, int, void**) (in /opt/install/qt/5.12.5/gcc_64/lib/libQt5Core.so.5.12.5)
==690288== by 0x95DE46: MAVLinkProtocol::messageReceived(LinkInterface*, __mavlink_message) (moc_MAVLinkProtocol.cpp:346)
==690288== by 0x757522: MAVLinkProtocol::receiveBytes(LinkInterface*, QByteArray) (MAVLinkProtocol.cc:362)
==690288== by 0x74C71E: QtPrivate::FunctorCall<QtPrivate::IndexesList<0, 1>, QtPrivate::List<LinkInterface*, QByteArray>, void, void (MAVLinkProtocol::*)(LinkInterface*, QByteArray)>::call(void (MAVLinkProtocol::*)(LinkInterface*, QByteArray), MAVLinkProtocol*, void**) (qobjectdefs_impl.h:152)
==690288== by 0x74BAB4: void QtPrivate::FunctionPointer<void (MAVLinkProtocol::*)(LinkInterface*, QByteArray)>::call<QtPrivate::List<LinkInterface*, QByteArray>, void>(void (MAVLinkProtocol::*)(LinkInterface*, QByteArray), MAVLinkProtocol*, void**) (qobjectdefs_impl.h:185)
==690288== by 0x74B3B7: QtPrivate::QSlotObject<void (MAVLinkProtocol::*)(LinkInterface*, QByteArray), QtPrivate::List<LinkInterface*, QByteArray>, void>::impl(int, QtPrivate::QSlotObjectBase*, QObject*, void**, bool*) (qobjectdefs_impl.h:414)
==690288== by 0x9D43DF5: QMetaObject::activate(QObject*, int, int, void**) (in /opt/install/qt/5.12.5/gcc_64/lib/libQt5Core.so.5.12.5)
* FTPManager: fix uninitialized Request
- Parts of the header were uninit
- zero init the payload allows for mavlink trimming
* Fix ~TerrainTile: use delete[] for arrays
* FactGroup: fix expensive & unnecessary object creation and map lookups
Every mavlink message reception was leading to creation of a list and
key lookup for each of the keys. This can easily be avoided and results
in noticeable reduction of CPU load (I'm seeing overall around 4% with
a pixhawk on USB).
The same pattern exists elsewhere as well
To have both order from the GCS and drone messages in logs
So that it's possible to analyze the complete exchange between QGC and the
drone.
- Add a signal emitted by writeBytes of each LinkInterface
- Connect this signal to MAVLinkProtocol::logSentBytes in LinkManager
- MAVLinkProtocol::logSentBytes will parse and log messages sent from
QGC
- Improve function names
- For notifications of an active link change only show the priority keyword if multiple links are connected
- Use QMap instead of QList for the HeartbeatTimers
- Style improvements
- Simplify sending the MAV_CMD_CONTROL_HIGH_LATENCY command
Add the HeartbeatTimer class to track a single heartbeat for a single link.
For every new received heartbeat an instance of the class is created.
Every instance emits a signal if it timed out or the timer is restarted.
Each vehicle then decides based on all different signals which link is the
priority link.