Browse Source

Change function name *changeSpeed to changeSpeedMetersSecond:

Ultimately it sends a MAV_CMD_DO_CHANGE_SPEED in meters
per second, so it is clearer if we have this name for the
function, could help avoiding confusion in the future
QGC4.4
davidsastresas 2 years ago committed by Don Gagne
parent
commit
4ff44aa82c
  1. 2
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 2
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  3. 4
      src/FirmwarePlugin/FirmwarePlugin.cc
  4. 4
      src/FirmwarePlugin/FirmwarePlugin.h
  5. 4
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  6. 4
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  7. 4
      src/FlightDisplay/GuidedActionsController.qml
  8. 8
      src/Vehicle/Vehicle.cc
  9. 4
      src/Vehicle/Vehicle.h

2
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -1162,7 +1162,7 @@ bool APMFirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) @@ -1162,7 +1162,7 @@ bool APMFirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle)
vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MAX");
}
void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv)
void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv)
{
vehicle->sendMavCommand(

2
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -83,7 +83,7 @@ public: @@ -83,7 +83,7 @@ public:
double maximumEquivalentAirspeed (Vehicle* vehicle) override;
double minimumEquivalentAirspeed (Vehicle* vehicle) override;
bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override;
void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override;
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) override;
protected:
/// All access to singleton is through stack specific implementation

4
src/FirmwarePlugin/FirmwarePlugin.cc

@ -276,14 +276,14 @@ void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double, bool pauseVehicl @@ -276,14 +276,14 @@ void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double, bool pauseVehicl
}
void
FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle*, double)
FirmwarePlugin::guidedModeChangeGroundSpeedMetersSecond(Vehicle*, double)
{
// Not supported by generic vehicle
qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
}
void
FirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle*, double)
FirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle*, double)
{
// Not supported by generic vehicle
qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);

4
src/FirmwarePlugin/FirmwarePlugin.h

@ -180,11 +180,11 @@ public: @@ -180,11 +180,11 @@ public:
/// Command vehicle to change groundspeed
/// @param groundspeed Groundspeed in m/s
virtual void guidedModeChangeGroundSpeed(Vehicle* vehicle, double groundspeed);
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed);
/// Command vehicle to change equivalent airspeed
/// @param airspeed_equiv Equivalent airspeed in m/s
virtual void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv);
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv);
/// Default tx mode to apply to joystick axes
/// TX modes are as outlined here: http://www.rc-airplane-world.com/rc-transmitter-modes.html

4
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -572,7 +572,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu @@ -572,7 +572,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
}
}
void PX4FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle* vehicle, double groundspeed)
void PX4FirmwarePlugin::guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed)
{
vehicle->sendMavCommand(
@ -586,7 +586,7 @@ void PX4FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle* vehicle, double gro @@ -586,7 +586,7 @@ void PX4FirmwarePlugin::guidedModeChangeGroundSpeed(Vehicle* vehicle, double gro
NAN, NAN,NAN); // param 5-7 unused
}
void PX4FirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv)
void PX4FirmwarePlugin::guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv)
{
vehicle->sendMavCommand(

4
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -53,8 +53,8 @@ public: @@ -53,8 +53,8 @@ public:
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;
void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override;
void guidedModeChangeGroundSpeedMetersSecond(Vehicle* vehicle, double groundspeed) override;
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle* vehicle, double airspeed_equiv) override;
void startMission (Vehicle* vehicle) override;
bool isGuidedMode (const Vehicle* vehicle) const override;
void initializeVehicle (Vehicle* vehicle) override;

4
src/FlightDisplay/GuidedActionsController.qml

@ -604,9 +604,9 @@ Item { @@ -604,9 +604,9 @@ Item {
// We need to convert back to m/s as that is what mavlink standard uses for MAV_CMD_DO_CHANGE_SPEED
var metersSecondSpeed = QGroundControl.unitsConversion.appSettingsSpeedUnitsToMetersSecond(sliderOutputValue).toFixed(1)
if (_activeVehicle.vtolInFwdFlight || _activeVehicle.fixedWing) {
_activeVehicle.guidedModeChangeEquivalentAirspeed(metersSecondSpeed)
_activeVehicle.guidedModeChangeEquivalentAirspeedMetersSecond(metersSecondSpeed)
} else {
_activeVehicle.guidedModeChangeGroundSpeed(metersSecondSpeed)
_activeVehicle.guidedModeChangeGroundSpeedMetersSecond(metersSecondSpeed)
}
}
break

8
src/Vehicle/Vehicle.cc

@ -2775,23 +2775,23 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle) @@ -2775,23 +2775,23 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
}
void
Vehicle::guidedModeChangeGroundSpeed(double groundspeed)
Vehicle::guidedModeChangeGroundSpeedMetersSecond(double groundspeed)
{
if (!guidedModeSupported()) {
qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeChangeGroundSpeed(this, groundspeed);
_firmwarePlugin->guidedModeChangeGroundSpeedMetersSecond(this, groundspeed);
}
void
Vehicle::guidedModeChangeEquivalentAirspeed(double airspeed)
Vehicle::guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed)
{
if (!guidedModeSupported()) {
qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
return;
}
_firmwarePlugin->guidedModeChangeEquivalentAirspeed(this, airspeed);
_firmwarePlugin->guidedModeChangeEquivalentAirspeedMetersSecond(this, airspeed);
}
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)

4
src/Vehicle/Vehicle.h

@ -378,10 +378,10 @@ public: @@ -378,10 +378,10 @@ public:
/// Command vehicle to change groundspeed
/// @param groundspeed Target horizontal groundspeed
Q_INVOKABLE void guidedModeChangeGroundSpeed (double groundspeed);
Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed);
/// Command vehicle to change equivalent airspeed
/// @param airspeed Target equivalent airspeed
Q_INVOKABLE void guidedModeChangeEquivalentAirspeed (double airspeed);
Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed);
/// Command vehicle to orbit given center point
/// @param centerCoord Orit around this point

Loading…
Cancel
Save