@@ -160,8 +160,8 @@ Item {
160
160
property bool showSetEstimatorOrigin: _activeVehicle && ! (_activeVehicle .sensorsPresentBits & Vehicle .SysStatusSensorGPS )
161
161
property bool showChangeHeading: _guidedActionsEnabled && _vehicleFlying
162
162
163
- property string changeSpeedTitle: _fixedWing ? changeAirspeedTitle : changeCruiseSpeedTitle
164
- property string changeSpeedMessage: _fixedWing ? changeAirspeedMessage : changeCruiseSpeedMessage
163
+ property string changeSpeedTitle: _vehicleInFwdFlight ? changeAirspeedTitle : changeCruiseSpeedTitle
164
+ property string changeSpeedMessage: _vehicleInFwdFlight ? changeAirspeedMessage : changeCruiseSpeedMessage
165
165
166
166
// Note: The '_missionItemCount - 2' is a hack to not trigger resume mission when a mission ends with an RTL item
167
167
property bool showResumeMission: _activeVehicle && ! _vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < _missionItemCount - 2 )
@@ -190,8 +190,8 @@ Item {
190
190
property bool _vehicleWasFlying: false
191
191
property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle .rcRSSI > 0 && _activeVehicle .rcRSSI <= 100 : false
192
192
property bool _fixedWingOnApproach: _activeVehicle ? _activeVehicle .fixedWing && _vehicleLanding : false
193
- property bool _fixedWing : _activeVehicle ? _activeVehicle .fixedWing || _activeVehicle . vtolInFwdFlight : false
194
- property bool _speedLimitsAvailable: _activeVehicle && ((_fixedWing && _activeVehicle .haveFWSpeedLimits ) || (! _fixedWing && _activeVehicle .haveMRSpeedLimits ))
193
+ property bool _vehicleInFwdFlight : _activeVehicle ? _activeVehicle .inFwdFlight : false
194
+ property bool _speedLimitsAvailable: _activeVehicle && ((_vehicleInFwdFlight && _activeVehicle .haveFWSpeedLimits ) || (! _vehicleInFwdFlight && _activeVehicle .haveMRSpeedLimits ))
195
195
property var _gripperFunction: undefined
196
196
197
197
// You can turn on log output for GuidedActionsController by turning on GuidedActionsControllerLog category
@@ -226,22 +226,22 @@ Item {
226
226
_unitsConversion .metersToAppSettingsVerticalDistanceUnits (_activeVehicle .minimumTakeoffAltitudeMeters ()),
227
227
qsTr (" Height (rel)" ))
228
228
} else if (actionCode === actionChangeSpeed) {
229
- if (_fixedWing ) {
229
+ if (_vehicleInFwdFlight ) {
230
230
guidedValueSlider .setupSlider (
231
231
GuidedValueSlider .SliderType .Speed ,
232
232
_unitsConversion .metersSecondToAppSettingsSpeedUnits (_activeVehicle .minimumEquivalentAirspeed ()).toFixed (1 ),
233
233
_unitsConversion .metersSecondToAppSettingsSpeedUnits (_activeVehicle .maximumEquivalentAirspeed ()).toFixed (1 ),
234
234
_unitsConversion .metersSecondToAppSettingsSpeedUnits (_activeVehicle .airSpeed .rawValue ),
235
235
qsTr (" Airspeed" ))
236
- } else if (! _fixedWing && _activeVehicle .haveMRSpeedLimits ) {
236
+ } else if (! _vehicleInFwdFlight && _activeVehicle .haveMRSpeedLimits ) {
237
237
guidedValueSlider .setupSlider (
238
238
GuidedValueSlider .SliderType .Speed ,
239
239
_unitsConversion .metersSecondToAppSettingsSpeedUnits (0.1 ).toFixed (1 ),
240
240
_unitsConversion .metersSecondToAppSettingsSpeedUnits (_activeVehicle .maximumHorizontalSpeedMultirotor ()).toFixed (1 ),
241
241
_unitsConversion .metersSecondToAppSettingsSpeedUnits (_activeVehicle .maximumHorizontalSpeedMultirotor ()/ 2 ).toFixed (1 ),
242
242
qsTr (" Speed" ))
243
243
} else {
244
- console .error (" setupSlider called for inapproproate change speed action" , _fixedWing , _activeVehicle .haveMRSpeedLimits )
244
+ console .error (" setupSlider called for inapproproate change speed action" , _vehicleInFwdFlight , _activeVehicle .haveMRSpeedLimits )
245
245
}
246
246
} else if (actionCode === actionChangeAlt || actionCode === actionOrbit || actionCode === actionGoto || actionCode === actionPause) {
247
247
guidedValueSlider .setupSlider (
@@ -686,7 +686,7 @@ Item {
686
686
if (_activeVehicle) {
687
687
// We need to convert back to m/s as that is what mavlink standard uses for MAV_CMD_DO_CHANGE_SPEED
688
688
var metersSecondSpeed = _unitsConversion .appSettingsSpeedUnitsToMetersSecond (sliderOutputValue)
689
- if (_activeVehicle . vtolInFwdFlight || _activeVehicle . fixedWing ) {
689
+ if (_vehicleInFwdFlight ) {
690
690
_activeVehicle .guidedModeChangeEquivalentAirspeedMetersSecond (metersSecondSpeed)
691
691
} else {
692
692
_activeVehicle .guidedModeChangeGroundSpeedMetersSecond (metersSecondSpeed)
0 commit comments