|
|
|
@ -35,8 +35,9 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
@@ -35,8 +35,9 @@ PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
PX4FirmwarePlugin::PX4FirmwarePlugin(void) |
|
|
|
|
: _manualFlightMode (tr("Manual")) |
|
|
|
|
PX4FirmwarePlugin::PX4FirmwarePlugin(MAV_TYPE vehicleType) |
|
|
|
|
: FirmwarePlugin(vehicleType) |
|
|
|
|
, _manualFlightMode (tr("Manual")) |
|
|
|
|
, _acroFlightMode (tr("Acro")) |
|
|
|
|
, _stabilizedFlightMode (tr("Stabilized")) |
|
|
|
|
, _rattitudeFlightMode (tr("Rattitude")) |
|
|
|
@ -257,7 +258,7 @@ FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData,
@@ -257,7 +258,7 @@ FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData,
|
|
|
|
|
qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData"; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return NULL; |
|
|
|
|
return nullptr; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) |
|
|
|
@ -306,22 +307,16 @@ QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
@@ -306,22 +307,16 @@ QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
|
|
|
|
|
switch (vehicleType) { |
|
|
|
|
case MAV_TYPE_GENERIC: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoCommon.json"); |
|
|
|
|
break; |
|
|
|
|
case MAV_TYPE_FIXED_WING: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json"); |
|
|
|
|
break; |
|
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json"); |
|
|
|
|
break; |
|
|
|
|
case MAV_TYPE_VTOL_QUADROTOR: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoVTOL.json"); |
|
|
|
|
break; |
|
|
|
|
case MAV_TYPE_SUBMARINE: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoSub.json"); |
|
|
|
|
break; |
|
|
|
|
case MAV_TYPE_GROUND_ROVER: |
|
|
|
|
return QStringLiteral(":/json/PX4/MavCmdInfoRover.json"); |
|
|
|
|
break; |
|
|
|
|
default: |
|
|
|
|
qWarning() << "PX4FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; |
|
|
|
|
return QString(); |
|
|
|
@ -410,13 +405,14 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel
@@ -410,13 +405,14 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel
|
|
|
|
|
qDebug() << takeoffAltRel << takeoffAltRelFromVehicle << takeoffAltAMSL << vehicleAltitudeAMSL; |
|
|
|
|
|
|
|
|
|
connect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult); |
|
|
|
|
vehicle->sendMavCommand(vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_NAV_TAKEOFF, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1, // No pitch requested
|
|
|
|
|
0, 0, // param 2-4 unused
|
|
|
|
|
NAN, NAN, NAN, // No yaw, lat, lon
|
|
|
|
|
takeoffAltAMSL); // AMSL altitude
|
|
|
|
|
vehicle->sendMavCommand( |
|
|
|
|
vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_NAV_TAKEOFF, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1, // No pitch requested
|
|
|
|
|
0, 0, // param 2-4 unused
|
|
|
|
|
NAN, NAN, NAN, // No yaw, lat, lon
|
|
|
|
|
static_cast<float>(takeoffAltAMSL)); // AMSL altitude
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) |
|
|
|
@ -446,8 +442,8 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
@@ -446,8 +442,8 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
|
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, |
|
|
|
|
NAN, |
|
|
|
|
gotoCoord.latitude(), |
|
|
|
|
gotoCoord.longitude(), |
|
|
|
|
static_cast<float>(gotoCoord.latitude()), |
|
|
|
|
static_cast<float>(gotoCoord.longitude()), |
|
|
|
|
vehicle->altitudeAMSL()->rawValue().toFloat()); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
@ -475,7 +471,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
@@ -475,7 +471,7 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
|
|
|
|
|
NAN, |
|
|
|
|
NAN, |
|
|
|
|
NAN, |
|
|
|
|
vehicle->homePosition().altitude() + newAltRel); |
|
|
|
|
static_cast<float>(vehicle->homePosition().altitude() + newAltRel)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::startMission(Vehicle* vehicle) |
|
|
|
@ -594,3 +590,8 @@ QString PX4FirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle){
@@ -594,3 +590,8 @@ QString PX4FirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle){
|
|
|
|
|
QString PX4FirmwarePlugin::_versionRegex() { |
|
|
|
|
return QStringLiteral("v([0-9,\\.]*) Stable"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool PX4FirmwarePlugin::supportsNegativeThrust(void) |
|
|
|
|
{ |
|
|
|
|
return _vehicleType == MAV_TYPE_GROUND_ROVER; |
|
|
|
|
} |
|
|
|
|