|
|
|
@ -7,10 +7,6 @@
@@ -7,10 +7,6 @@
|
|
|
|
|
* |
|
|
|
|
****************************************************************************/ |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/// @file
|
|
|
|
|
/// @author Don Gagne <don@thegagnes.com>
|
|
|
|
|
|
|
|
|
|
#include "PX4FirmwarePlugin.h" |
|
|
|
|
#include "PX4ParameterMetaData.h" |
|
|
|
|
#include "QGCApplication.h" |
|
|
|
@ -462,7 +458,54 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
@@ -462,7 +458,54 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) |
|
|
|
|
typedef struct { |
|
|
|
|
PX4FirmwarePlugin* plugin; |
|
|
|
|
Vehicle* vehicle; |
|
|
|
|
double newAMSLAlt; |
|
|
|
|
} PauseVehicleThenChangeAltData_t; |
|
|
|
|
|
|
|
|
|
static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int /*compId*/, MAV_RESULT commandResult, Vehicle::MavCmdResultFailureCode_t failureCode) |
|
|
|
|
{ |
|
|
|
|
if (commandResult != MAV_RESULT_ACCEPTED) { |
|
|
|
|
switch (failureCode) { |
|
|
|
|
case Vehicle::MavCmdResultCommandResultOnly: |
|
|
|
|
qDebug() << QStringLiteral("MAV_CMD_DO_REPOSITION error(%1)").arg(commandResult); |
|
|
|
|
break; |
|
|
|
|
case Vehicle::MavCmdResultFailureNoResponseToCommand: |
|
|
|
|
qDebug() << "MAV_CMD_DO_REPOSITION no response from vehicle"; |
|
|
|
|
break; |
|
|
|
|
case Vehicle::MavCmdResultFailureDuplicateCommand: |
|
|
|
|
qDebug() << "Internal Error: MAV_CMD_DO_REPOSITION could not be sent due to duplicate command"; |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData); |
|
|
|
|
pData->plugin->_changeAltAfterPause(resultHandlerData, commandResult == MAV_RESULT_ACCEPTED /* pauseSucceeded */); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::_changeAltAfterPause(void* resultHandlerData, bool pauseSucceeded) |
|
|
|
|
{ |
|
|
|
|
PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData); |
|
|
|
|
|
|
|
|
|
if (pauseSucceeded) { |
|
|
|
|
pData->vehicle->sendMavCommand( |
|
|
|
|
pData->vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1.0f, // Don't change groundspeed
|
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, // Reserved
|
|
|
|
|
qQNaN(), qQNaN(), qQNaN(), // No change to yaw, lat, lon
|
|
|
|
|
static_cast<float>(pData->newAMSLAlt)); |
|
|
|
|
} else { |
|
|
|
|
qgcApp()->showAppMessage(tr("Unable to pause vehicle.")); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
delete pData; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange, bool pauseVehicle) |
|
|
|
|
{ |
|
|
|
|
if (!vehicle->homePosition().isValid()) { |
|
|
|
|
qgcApp()->showAppMessage(tr("Unable to change altitude, home position unknown.")); |
|
|
|
@ -476,16 +519,24 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
@@ -476,16 +519,24 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
|
|
|
|
|
double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble(); |
|
|
|
|
double newAltRel = currentAltRel + altitudeChange; |
|
|
|
|
|
|
|
|
|
vehicle->sendMavCommand(vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1.0f, |
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, |
|
|
|
|
NAN, |
|
|
|
|
NAN, |
|
|
|
|
NAN, |
|
|
|
|
static_cast<float>(vehicle->homePosition().altitude() + newAltRel)); |
|
|
|
|
PauseVehicleThenChangeAltData_t* resultData = new PauseVehicleThenChangeAltData_t; |
|
|
|
|
resultData->plugin = this; |
|
|
|
|
resultData->vehicle = vehicle; |
|
|
|
|
resultData->newAMSLAlt = vehicle->homePosition().altitude() + newAltRel; |
|
|
|
|
|
|
|
|
|
if (pauseVehicle) { |
|
|
|
|
vehicle->sendMavCommandWithHandler( |
|
|
|
|
_pauseVehicleThenChangeAltResultHandler, |
|
|
|
|
resultData, |
|
|
|
|
vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
-1.0f, // Don't change groundspeed
|
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, // Reserved
|
|
|
|
|
qQNaN(), qQNaN(), qQNaN(), qQNaN()); // No change to yaw, lat, lon, alt
|
|
|
|
|
} else { |
|
|
|
|
_changeAltAfterPause(resultData, true /* pauseSucceeded */); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::startMission(Vehicle* vehicle) |
|
|
|
|