11#include <QtQml/QQmlEngine>
17 , timeScale(timeScale_)
24MAVLinkInspectorController::Range_st::Range_st(
const QString &label_, qreal range_)
35 , _updateFrequencyTimer(new QTimer(this))
47 (void) connect(_updateFrequencyTimer, &QTimer::timeout,
this, &MAVLinkInspectorController::_refreshFrequency);
49 _updateFrequencyTimer->setInterval(1000);
50 _updateFrequencyTimer->setSingleShot(
false);
51 _updateFrequencyTimer->start();
53 _timeScaleSt.append(
new TimeScale_st(tr(
"5 Sec"), 5 * 1000));
54 _timeScaleSt.append(
new TimeScale_st(tr(
"10 Sec"), 10 * 1000));
55 _timeScaleSt.append(
new TimeScale_st(tr(
"30 Sec"), 30 * 1000));
56 _timeScaleSt.append(
new TimeScale_st(tr(
"60 Sec"), 60 * 1000));
57 _timeScaleSt.append(
new TimeScale_st(tr(
"2 Min"), 120 * 1000));
58 _timeScaleSt.append(
new TimeScale_st(tr(
"5 Min"), 300 * 1000));
60 _rangeSt.append(
new Range_st(tr(
"Auto"), 0));
61 _rangeSt.append(
new Range_st(tr(
"10,000"), 10000));
62 _rangeSt.append(
new Range_st(tr(
"1,000"), 1000));
63 _rangeSt.append(
new Range_st(tr(
"100"), 100));
64 _rangeSt.append(
new Range_st(tr(
"10"), 10));
65 _rangeSt.append(
new Range_st(tr(
"1"), 1));
66 _rangeSt.append(
new Range_st(tr(
"0.1"), 0.1));
67 _rangeSt.append(
new Range_st(tr(
"0.01"), 0.01));
68 _rangeSt.append(
new Range_st(tr(
"0.001"), 0.001));
69 _rangeSt.append(
new Range_st(tr(
"0.0001"), 0.0001));
74 qDeleteAll(_timeScaleSt);
84 for (
int i = 0; i < _systems->
count(); i++) {
85 const QGCMAVLinkSystem *
const system = qobject_cast<const QGCMAVLinkSystem*>(_systems->
get(i));
87 names << tr(
"System %1").arg(system->
id());
95 if (_timeScales.isEmpty()) {
96 for (
const TimeScale_st *timeScale : _timeScaleSt) {
97 _timeScales << timeScale->label;
106 if (_rangeList.isEmpty()) {
107 for (
const Range_st *range : _rangeSt) {
108 _rangeList << range->label;
115void MAVLinkInspectorController::_setActiveVehicle(
Vehicle *vehicle)
120 _activeSystem = system;
122 _activeSystem =
nullptr;
125 _activeSystem =
nullptr;
133 for (
int i = 0; i < _systems->
count(); i++) {
135 if (system && (system->
id() ==
id)) {
143void MAVLinkInspectorController::_refreshFrequency()
145 for (
int i = 0; i < _systems->
count(); i++) {
151 for (
int messageIndex = 0; messageIndex < system->
messages()->count(); messageIndex++) {
160void MAVLinkInspectorController::_vehicleAdded(
Vehicle *vehicle)
172 for (
int i = 0; i < sys->
messages()->count(); i++) {
174 if ((msg->
compId() == compid) && (msg->
id() == msgId)) {
184void MAVLinkInspectorController::_vehicleRemoved(
const Vehicle *vehicle)
191 system->deleteLater();
210 if (!_activeSystem) {
211 _activeSystem = system;
215 msg = system->
findMessage(message.msgid, message.compid, instanceValue);
229 if (system != _activeSystem) {
230 _activeSystem = system;
237 if (!_activeSystem) {
242 if (!multiVehicleManager) {
246 const uint8_t sysId = _selectedSystemID();
261 const uint8_t compId = _selectedComponentID();
270uint8_t MAVLinkInspectorController::_selectedSystemID()
const
272 return (_activeSystem ? _activeSystem->
id() : 0);
275uint8_t MAVLinkInspectorController::_selectedComponentID()
const
278 return (msg ? msg->
compId() : 0);
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
The link interface defines the interface for all links used to communicate with the ground station ap...
MAVLink message inspector controller (provides the logic for UI display)
Q_INVOKABLE void setActiveSystem(int systemId)
void activeSystemChanged()
QStringList systemNames() const
~MAVLinkInspectorController()
Q_INVOKABLE void setMessageInterval(int32_t rate) const
MAVLinkInspectorController(QObject *parent=nullptr)
MAVLink micro air vehicle protocol reference implementation.
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
static MAVLinkProtocol * instance()
static MultiVehicleManager * instance()
void vehicleAdded(Vehicle *vehicle)
void vehicleRemoved(Vehicle *vehicle)
void activeVehicleChanged(Vehicle *activeVehicle)
Q_INVOKABLE Vehicle * getVehicleById(int vehicleId) const
void setTargetRateHz(int32_t rate)
void update(const mavlink_message_t &message)
static QString extractInstanceValue(const mavlink_message_t &message)
Extract the instance field value from a raw mavlink message, or empty string if none.
QmlObjectListModel * messages() const
QGCMAVLinkMessage * selectedMsg()
QGCMAVLinkMessage * findMessage(uint32_t id, uint8_t compId, const QString &instanceValue=QString())
void append(QGCMAVLinkMessage *message)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
Q_INVOKABLE QObject * get(int index)
QObject * removeOne(const QObject *object) override final
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)