Skip to content

Commit b02cd51

Browse files
committed
Add periodic RC override sending.
Fix PWM input fields update
1 parent 7afaa5e commit b02cd51

14 files changed

+155
-50
lines changed

src/AnalyzeView/MAVLinkInspectorController.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ class QGCMAVLinkMessage : public QObject {
9595
Q_PROPERTY(QString name READ name CONSTANT)
9696
Q_PROPERTY(qreal messageHz READ messageHz NOTIFY freqChanged)
9797
Q_PROPERTY(quint64 count READ count NOTIFY countChanged)
98+
Q_PROPERTY(int mavlinkVer READ mavlinkVer CONSTANT)
9899
Q_PROPERTY(QmlObjectListModel* fields READ fields CONSTANT)
99100
Q_PROPERTY(bool fieldSelected READ fieldSelected NOTIFY fieldSelectedChanged)
100101
Q_PROPERTY(bool selected READ selected NOTIFY selectedChanged)
@@ -107,6 +108,7 @@ class QGCMAVLinkMessage : public QObject {
107108
QString name () { return _name; }
108109
qreal messageHz () const{ return _messageHz; }
109110
quint64 count () const{ return _count; }
111+
int mavlinkVer () const{ return _message.magic == 0xFE ? 1 : 2; }
110112
quint64 lastCount () const{ return _lastCount; }
111113
QmlObjectListModel* fields () { return &_fields; }
112114
bool fieldSelected () const{ return _fieldSelected; }

src/AnalyzeView/MAVLinkInspectorPage.qml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -158,6 +158,12 @@ AnalyzePage {
158158
QGCLabel {
159159
text: curMessage ? curMessage.count : ""
160160
}
161+
QGCLabel {
162+
text: qsTr("Mavlink ver:")
163+
}
164+
QGCLabel {
165+
text: curMessage ? curMessage.mavlinkVer : ""
166+
}
161167
}
162168
Item { height: ScreenTools.defaultFontPixelHeight; width: 1 }
163169
//---------------------------------------------------------

src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -260,6 +260,7 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* /*vehicle*/, mavlink_
260260
// and lower the severity on them so that they don't pop in the users face.
261261

262262
QString messageText = _getMessageText(message);
263+
qDebug(APMFirmwarePluginLog) << "StatusText: " << messageText;
263264
if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) {
264265
_adjustCalibrationMessageSeverity(message);
265266
return true;
@@ -1073,3 +1074,8 @@ QMutex& APMFirmwarePlugin::_reencodeMavlinkChannelMutex()
10731074
static QMutex _mutex{};
10741075
return _mutex;
10751076
}
1077+
1078+
bool APMFirmwarePlugin::supportsRcChannelOverride(void)
1079+
{
1080+
return true;
1081+
}

src/FirmwarePlugin/APM/APMFirmwarePlugin.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,9 +77,10 @@ class APMFirmwarePlugin : public FirmwarePlugin
7777
QObject* _loadParameterMetaData (const QString& metaDataFile) override;
7878
QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
7979
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
80-
QString getHobbsMeter (Vehicle* vehicle) override;
80+
QString getHobbsMeter (Vehicle* vehicle) override;
8181
bool hasGripper (const Vehicle* vehicle) const override;
8282
const QVariantList& toolIndicators (const Vehicle* vehicle) override;
83+
bool supportsRcChannelOverride(void) override;
8384

8485
protected:
8586
/// All access to singleton is through stack specific implementation

src/FirmwarePlugin/FirmwarePlugin.cc

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -154,6 +154,11 @@ bool FirmwarePlugin::supportsJSButton(void)
154154
return false;
155155
}
156156

157+
bool FirmwarePlugin::supportsRcChannelOverride(void)
158+
{
159+
return false;
160+
}
161+
157162
bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
158163
{
159164
Q_UNUSED(vehicle);

src/FirmwarePlugin/FirmwarePlugin.h

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -211,6 +211,10 @@ class FirmwarePlugin : public QObject
211211
/// to be assigned via parameters in firmware. Default is false.
212212
virtual bool supportsJSButton(void);
213213

214+
/// Returns true if the firmware supports the mavlink RC_CHANNELS_OVERRIDE message
215+
/// Default is false.
216+
virtual bool supportsRcChannelOverride(void);
217+
214218
/// Returns true if the firmware supports calibrating motor interference offsets for the compass
215219
/// (CompassMot). Default is true.
216220
virtual bool supportsMotorInterference(void);

src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -736,4 +736,9 @@ bool PX4FirmwarePlugin::hasGripper(const Vehicle* vehicle) const
736736
return _hasGripper;
737737
}
738738
return false;
739+
}
740+
741+
bool PX4FirmwarePlugin::supportsRcChannelOverride(void)
742+
{
743+
return false;
739744
}

src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,7 @@ class PX4FirmwarePlugin : public FirmwarePlugin
7373
bool supportsNegativeThrust (Vehicle* vehicle) override;
7474
QString getHobbsMeter (Vehicle* vehicle) override;
7575
bool hasGripper (const Vehicle* vehicle) const override;
76+
bool supportsRcChannelOverride (void) override;
7677

7778
protected:
7879
typedef struct {

src/Joystick/Joystick.cc

Lines changed: 64 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@
1010

1111
#include "Joystick.h"
1212
#include "QGC.h"
13-
#include "AutoPilotPlugin.h"
1413
#include "UAS.h"
1514
#include "QGCApplication.h"
1615
#include "VideoManager.h"
@@ -88,6 +87,7 @@ const float Joystick::_minAxisFrequencyHz = 0.25f;
8887
const float Joystick::_maxAxisFrequencyHz = 200.0f;
8988
const float Joystick::_minButtonFrequencyHz = 0.25f;
9089
const float Joystick::_maxButtonFrequencyHz = 50.0f;
90+
const float Joystick::_rcOverrideFrequencyHz = 0.5f;
9191

9292
AssignedButtonAction::AssignedButtonAction(QObject* parent, const QString action)
9393
: QObject(parent)
@@ -109,28 +109,28 @@ AssignedButtonAction::AssignedButtonAction(
109109
{
110110
}
111111

112-
void AssignedButtonAction::sendPwm(Vehicle *vehicle, bool buttonDown)
112+
int16_t AssignedButtonAction::calculatePwm(Vehicle *vehicle, bool buttonDown)
113113
{
114114
if (!_isPwmOverrideAction) {
115115
qCWarning(JoystickLog) << "send called on non-pwm action";
116-
return;
116+
return -1;
117117
}
118118

119119
uint16_t pwmValue = buttonDown ? _hiPwmValue : _loPwmValue;
120120
if (_pwmLatchMode) {
121121
qCDebug(JoystickLog) << "Latch mode, current saved button state " << (_pwmLatchButtonDown ? "down" : "up");
122122

123123
if (buttonDown) {
124+
// altering latch state
124125
_pwmLatchButtonDown = !_pwmLatchButtonDown;
125-
pwmValue = _pwmLatchButtonDown ? _hiPwmValue : _loPwmValue;
126-
} else {
127-
qCDebug(JoystickLog) << "since button is up - exiting";
128-
return;
129126
}
127+
pwmValue = _pwmLatchButtonDown ? _hiPwmValue : _loPwmValue;
130128
}
131129

132-
qCDebug(JoystickLog) << " Sending PWM Value " << pwmValue;
133-
vehicle->rcChannelOverride(_pwmRcChannel, pwmValue);
130+
qCDebug(JoystickLog) << " Calculated PWM Value " << pwmValue << " for action " << _action;
131+
//vehicle->rcChannelOverride(_pwmRcChannel, pwmValue);
132+
133+
return pwmValue;
134134
}
135135

136136
uint8_t AssignedButtonAction::getRcChannelFromAction(const QString action)
@@ -162,11 +162,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
162162
, _totalButtonCount(_buttonCount+_hatButtonCount)
163163
, _multiVehicleManager(multiVehicleManager)
164164
{
165-
<<<<<<< HEAD
166165
qRegisterMetaType<GRIPPER_ACTIONS>();
167166

168-
=======
169-
>>>>>>> Refactor for clearness
170167
_rgAxisValues = new int[static_cast<size_t>(_axisCount)];
171168
_rgCalibration = new Calibration_t[static_cast<size_t>(_axisCount)];
172169
_rgButtonValues = new uint8_t[static_cast<size_t>(_totalButtonCount)];
@@ -177,6 +174,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
177174
_rgButtonValues[i] = BUTTON_UP;
178175
_buttonActionArray.append(nullptr);
179176
}
177+
180178
_buildActionList(_multiVehicleManager->activeVehicle());
181179
_updateTXModeSettingsKey(_multiVehicleManager->activeVehicle());
182180
_loadSettings();
@@ -277,6 +275,7 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle)
277275
int mode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt();
278276
setTXMode(mode);
279277
}
278+
_clearRcOverrideButtonActions();
280279
}
281280

282281
void Joystick::_loadSettings()
@@ -384,7 +383,7 @@ void Joystick::_loadSettings()
384383
_buttonActionArray[button]->buttonTime().start();
385384

386385
bool savedRepeatState = settings.value(QString(_buttonActionRepeatKey).arg(button), false).toBool();
387-
setButtonRepeatIfAvailable(button, savedRepeatState);
386+
_setButtonRepeatIfAvailable(button, savedRepeatState);
388387

389388
qCDebug(JoystickLog) << "_loadSettings button:action" << button << _buttonActionArray[button]->action()
390389
<< _buttonActionArray[button]->repeat();
@@ -411,7 +410,6 @@ void Joystick::_saveButtonSettings()
411410
settings.setValue(QString(_buttonActionLowPwmValueKey).arg(button), _buttonActionArray[button]->lowPwm());
412411
settings.setValue(QString(_buttonActionHighPwmValueKey).arg(button), _buttonActionArray[button]->highPwm());
413412
settings.setValue(QString(_buttonActionLatchPwmValueKey).arg(button), _buttonActionArray[button]->pwmLatchMode());
414-
415413
}
416414
}
417415
}
@@ -567,6 +565,7 @@ void Joystick::run()
567565
_open();
568566
//-- Reset timers
569567
_axisTime.start();
568+
_rcOverrideTimer.start();
570569
for (int buttonIndex = 0; buttonIndex < _totalButtonCount; buttonIndex++) {
571570
if(_buttonActionArray[buttonIndex]) {
572571
_buttonActionArray[buttonIndex]->buttonTime().start();
@@ -576,6 +575,7 @@ void Joystick::run()
576575
_update();
577576
_handleButtons();
578577
_handleAxis();
578+
_handleRcOverride();
579579
QGC::SLEEP::msleep(qMin(static_cast<int>(1000.0f / _maxAxisFrequencyHz), static_cast<int>(1000.0f / _maxButtonFrequencyHz)) / 2);
580580
}
581581
_close();
@@ -775,6 +775,26 @@ void Joystick::_handleAxis()
775775
}
776776
}
777777

778+
void Joystick::_handleRcOverride()
779+
{
780+
if (!_activeVehicle || !_activeVehicle->supportsRcChannelOverride()) {
781+
return;
782+
}
783+
const int rcOverrideInterval = static_cast<int>(1000.0f / _rcOverrideFrequencyHz);
784+
785+
if (_rcOverrideActive || _rcOverrideTimer.elapsed() > rcOverrideInterval) {
786+
_rcOverrideActive = false;
787+
_rcOverrideTimer.start();
788+
uint16_t overrideData[18] = {UINT16_MAX};
789+
overrideData[16] = _mapRcOverrideToRelease(17, 0);
790+
overrideData[17] = _mapRcOverrideToRelease(18, 0);
791+
for (int i = 0; i < MAX_RC_CHANNELS; i++) {
792+
overrideData[i] = _rcOverride[i] == -1 ? _mapRcOverrideToRelease(i + 1, 0) : _rcOverride[i];
793+
}
794+
_activeVehicle->rcChannelsOverride(overrideData);
795+
}
796+
}
797+
778798
void Joystick::startPolling(Vehicle* vehicle)
779799
{
780800
if (vehicle) {
@@ -907,7 +927,7 @@ void Joystick::setButtonAction(int button, const QString& action)
907927
if (action.isEmpty() || action == _buttonActionNone) {
908928
_pwmSettingsVisibilities[button] = false;
909929
if (_buttonActionArray[button]) {
910-
removeButtonSettings(button);
930+
_removeButtonSettings(button);
911931
_buttonActionArray[button]->deleteLater();
912932
_buttonActionArray[button] = nullptr;
913933
}
@@ -917,7 +937,7 @@ void Joystick::setButtonAction(int button, const QString& action)
917937
qCDebug(JoystickLog) << "setButtonAction: isPwmAction " << isPwmAction;
918938

919939
if (!_buttonActionArray[button]) {
920-
_buttonActionArray[button] = isPwmAction ? new AssignedButtonAction(this, action, 1000, 2000, false)
940+
_buttonActionArray[button] = isPwmAction ? new AssignedButtonAction(this, action, 1500, 1500, false)
921941
: new AssignedButtonAction(this, action);
922942
} else {
923943
if (isPwmAction) {
@@ -935,14 +955,14 @@ void Joystick::setButtonAction(int button, const QString& action)
935955
}
936956

937957
//-- Make sure repeat is off if this action doesn't support repeats
938-
setButtonRepeatIfAvailable(button, false);
939-
saveButtonSettings(button);
958+
_setButtonRepeatIfAvailable(button, false);
959+
_saveButtonSettings(button);
940960
}
941961
emit pwmVisibilitiesChanged();
942962
emit buttonActionsChanged();
943963
}
944964

945-
void Joystick::setButtonRepeatIfAvailable(int button, bool repeat)
965+
void Joystick::_setButtonRepeatIfAvailable(int button, bool repeat)
946966
{
947967
int idx = _findAssignableButtonAction(_buttonActionArray[button]->action());
948968
if (idx >= 0) {
@@ -955,7 +975,7 @@ void Joystick::setButtonRepeatIfAvailable(int button, bool repeat)
955975
_buttonActionArray[button]->repeat(false);
956976
}
957977

958-
void Joystick::saveButtonSettings(int button)
978+
void Joystick::_saveButtonSettings(int button)
959979
{
960980
QSettings settings;
961981
settings.beginGroup(_settingsGroup);
@@ -970,7 +990,7 @@ void Joystick::saveButtonSettings(int button)
970990
}
971991
}
972992

973-
void Joystick::removeButtonSettings(int button)
993+
void Joystick::_removeButtonSettings(int button)
974994
{
975995
QSettings settings;
976996
settings.beginGroup(_settingsGroup);
@@ -1349,10 +1369,10 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
13491369
_assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGripperGrab));
13501370
_assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionGripperRelease));
13511371

1352-
// TODO(bzd) take channel nos from config, especially max
1353-
for (int ch = 8; ch <= 16;ch++) {
1354-
_assignableButtonActions.append(new AssignableButtonAction(this, QString("Channel %1 direct PWM").arg(ch)));
1372+
for (int ch = 8; ch <= MAX_RC_CHANNELS; ch++) {
1373+
_assignableButtonActions.append(new AssignableButtonAction(this, QString("Channel %1 direct PWM").arg(ch)));
13551374
}
1375+
_clearRcOverrideButtonActions();
13561376

13571377
_assignableButtonActions.append(new AssignableButtonAction(this, _buttonActionEmergencyStop));
13581378
for (auto& item : _customMavCommands) {
@@ -1369,8 +1389,27 @@ void Joystick::_buildActionList(Vehicle* activeVehicle)
13691389
bool Joystick::_executeRcOverrideButtonAction(int buttonIndex, bool buttonDown)
13701390
{
13711391
if (_buttonActionArray[buttonIndex]) {
1372-
_buttonActionArray[buttonIndex]->sendPwm(_activeVehicle, buttonDown);
1392+
uint8_t channel = _buttonActionArray[buttonIndex]->rcChannel();
1393+
auto pwm = _buttonActionArray[buttonIndex]->calculatePwm(_activeVehicle, buttonDown);
1394+
_rcOverride[channel-1] = pwm;
1395+
_rcOverrideActive = true;
13731396
return true;
13741397
}
13751398
return false;
13761399
}
1400+
1401+
void Joystick::_clearRcOverrideButtonActions() {
1402+
qCDebug(JoystickLog) << "Clearing RC override button actions";
1403+
for (int i = 0; i < MAX_RC_CHANNELS; i++) {
1404+
_rcOverride[i] = -1;
1405+
}
1406+
}
1407+
1408+
uint16_t Joystick::_mapRcOverrideToRelease(uint8_t rcChannel, uint16_t value) {
1409+
// UINT16_MAX - ignore
1410+
// 0 Release
1411+
if (value == 0) {
1412+
return rcChannel < 9 ? 0 : UINT16_MAX - 1;
1413+
}
1414+
return value;
1415+
}

0 commit comments

Comments
 (0)