Browse Source

only show speed change action if speed limits are known

Signed-off-by: RomanBapst <bapstroman@gmail.com>
QGC4.4
RomanBapst 3 years ago committed by Ramon Roche
parent
commit
2c19a68eeb
  1. 6
      src/FirmwarePlugin/FirmwarePlugin.h
  2. 11
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  3. 2
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  4. 3
      src/FlightDisplay/GuidedActionsController.qml
  5. 6
      src/Vehicle/Vehicle.cc
  6. 11
      src/Vehicle/Vehicle.h

6
src/FirmwarePlugin/FirmwarePlugin.h

@ -159,6 +159,12 @@ public: @@ -159,6 +159,12 @@ public:
/// @return The minimum equivalent airspeed setpoint
virtual double minimumEquivalentAirspeed(Vehicle* /*vehicle*/) { return NAN; }
/// @return Return true if we have received the ground speed limits for the mulirotor.
virtual bool mulirotorSpeedLimitsAvailable(Vehicle* /*vehicle*/) { return false; }
/// @return Return true if we have received the airspeed limits for fixed wing.
virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle* /*vehicle*/) { return false; }
/// Command the vehicle to start the mission
virtual void startMission(Vehicle* vehicle);

11
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -442,6 +442,17 @@ double PX4FirmwarePlugin::minimumEquivalentAirspeed(Vehicle* vehicle) @@ -442,6 +442,17 @@ double PX4FirmwarePlugin::minimumEquivalentAirspeed(Vehicle* vehicle)
return FirmwarePlugin::minimumEquivalentAirspeed(vehicle);
}
bool PX4FirmwarePlugin::mulirotorSpeedLimitsAvailable(Vehicle* vehicle)
{
return vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "MPC_XY_VEL_MAX");
}
bool PX4FirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle)
{
return vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "FW_AIRSPD_MIN") &&
vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "FW_AIRSPD_MAX");
}
void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {

2
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -49,6 +49,8 @@ public: @@ -49,6 +49,8 @@ public:
double maximumHorizontalSpeedMultirotor(Vehicle* vehicle) override;
double maximumEquivalentAirspeed(Vehicle* vehicle) override;
double minimumEquivalentAirspeed(Vehicle* vehicle) override;
bool mulirotorSpeedLimitsAvailable(Vehicle* vehicle) override;
bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override;
void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) override;
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel, bool pauseVehicle) override;
void guidedModeChangeGroundSpeed (Vehicle* vehicle, double groundspeed) override;

3
src/FlightDisplay/GuidedActionsController.qml

@ -122,7 +122,7 @@ Item { @@ -122,7 +122,7 @@ Item {
property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleArmed && _vehicleFlying && (_currentMissionIndex < _missionItemCount - 1)
property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused && !_fixedWingOnApproach
property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive
property bool showChangeSpeed: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive
property bool showChangeSpeed: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive && _speedLimitsAvailable
property bool showOrbit: _guidedActionsEnabled && _vehicleFlying && __orbitSupported && !_missionActive
property bool showROI: _guidedActionsEnabled && _vehicleFlying && __roiSupported && !_missionActive
property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _fixedWingOnApproach
@ -159,6 +159,7 @@ Item { @@ -159,6 +159,7 @@ Item {
property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false
property bool _fixedWingOnApproach: _activeVehicle ? _activeVehicle.fixedWing && _vehicleLanding : false
property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing || _activeVehicle.vtolInFwdFlight : false
property bool _speedLimitsAvailable: _activeVehicle && ((_fixedWing && _activeVehicle.haveFWSpeedLimits) || (!_fixedWing && _activeVehicle.haveMRSpeedLimits))
// You can turn on log output for GuidedActionsController by turning on GuidedActionsControllerLog category
property bool __guidedModeSupported: _activeVehicle ? _activeVehicle.guidedModeSupported : false

6
src/Vehicle/Vehicle.cc

@ -2266,6 +2266,12 @@ void Vehicle::_parametersReady(bool parametersReady) @@ -2266,6 +2266,12 @@ void Vehicle::_parametersReady(bool parametersReady)
_setupAutoDisarmSignalling();
_initialConnectStateMachine->advance();
}
_multirotor_speed_limits_available = _firmwarePlugin->mulirotorSpeedLimitsAvailable(this);
_fixed_wing_airspeed_limits_available = _firmwarePlugin->fixedWingAirSpeedLimitsAvailable(this);
emit haveMRSpeedLimChanged();
emit haveFWSpeedLimChanged();
}
void Vehicle::_sendQGCTimeToVehicle()

11
src/Vehicle/Vehicle.h

@ -271,6 +271,8 @@ public: @@ -271,6 +271,8 @@ public:
Q_PROPERTY(bool roiModeSupported READ roiModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(QString gotoFlightMode READ gotoFlightMode CONSTANT) ///< Flight mode vehicle is in while performing goto
Q_PROPERTY(bool haveMRSpeedLimits READ haveMRSpeedLimits NOTIFY haveMRSpeedLimChanged)
Q_PROPERTY(bool haveFWSpeedLimits READ haveFWSpeedLimits NOTIFY haveFWSpeedLimChanged)
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
Q_PROPERTY(VehicleLinkManager* vehicleLinkManager READ vehicleLinkManager CONSTANT)
@ -461,6 +463,9 @@ public: @@ -461,6 +463,9 @@ public:
bool takeoffVehicleSupported () const;
QString gotoFlightMode () const;
bool haveMRSpeedLimits() const { return _multirotor_speed_limits_available; }
bool haveFWSpeedLimits() const { return _fixed_wing_airspeed_limits_available; }
// Property accessors
QGeoCoordinate coordinate() { return _coordinate; }
@ -912,6 +917,8 @@ signals: @@ -912,6 +917,8 @@ signals:
void readyToFlyChanged (bool readyToFy);
void allSensorsHealthyChanged (bool allSensorsHealthy);
void requiresGpsFixChanged ();
void haveMRSpeedLimChanged ();
void haveFWSpeedLimChanged ();
void firmwareVersionChanged ();
void firmwareCustomVersionChanged ();
@ -1294,6 +1301,10 @@ private: @@ -1294,6 +1301,10 @@ private:
float _altitudeTuningOffset = qQNaN(); // altitude offset, so the plotted value is around 0
// these flags are used to determine if the speed change action from fly view should be shown
bool _multirotor_speed_limits_available = false;
bool _fixed_wing_airspeed_limits_available = false;
// FactGroup facts
Fact _rollFact;

Loading…
Cancel
Save