|
|
|
@ -428,16 +428,30 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
@@ -428,16 +428,30 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
vehicle->sendMavCommand(vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1.0f, |
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, |
|
|
|
|
NAN, |
|
|
|
|
gotoCoord.latitude(), |
|
|
|
|
gotoCoord.longitude(), |
|
|
|
|
vehicle->altitudeAMSL()->rawValue().toFloat()); |
|
|
|
|
if (vehicle->capabilityBits() && MAV_PROTOCOL_CAPABILITY_COMMAND_INT) { |
|
|
|
|
vehicle->sendMavCommandInt(vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
MAV_FRAME_GLOBAL, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1.0f, |
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, |
|
|
|
|
NAN, |
|
|
|
|
gotoCoord.latitude(), |
|
|
|
|
gotoCoord.longitude(), |
|
|
|
|
vehicle->altitudeAMSL()->rawValue().toFloat()); |
|
|
|
|
} else { |
|
|
|
|
vehicle->sendMavCommand(vehicle->defaultComponentId(), |
|
|
|
|
MAV_CMD_DO_REPOSITION, |
|
|
|
|
true, // show error is fails
|
|
|
|
|
-1.0f, |
|
|
|
|
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, |
|
|
|
|
0.0f, |
|
|
|
|
NAN, |
|
|
|
|
gotoCoord.latitude(), |
|
|
|
|
gotoCoord.longitude(), |
|
|
|
|
vehicle->altitudeAMSL()->rawValue().toFloat()); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange) |
|
|
|
|