Commit fcf9a1dc authored by DonLakeFlyer's avatar DonLakeFlyer

Move VTOL fixes

parent ff6dedad
...@@ -354,6 +354,13 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess ...@@ -354,6 +354,13 @@ bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_mess
int supportedMinorNumber = -1; int supportedMinorNumber = -1;
switch (vehicle->vehicleType()) { switch (vehicle->vehicleType()) {
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
supportedMajorNumber = 3; supportedMajorNumber = 3;
supportedMinorNumber = 4; supportedMinorNumber = 4;
...@@ -602,6 +609,13 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle) ...@@ -602,6 +609,13 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
case MAV_TYPE_HELICOPTER: case MAV_TYPE_HELICOPTER:
vehicle->setFirmwareVersion(3, 4, 0); vehicle->setFirmwareVersion(3, 4, 0);
break; break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
vehicle->setFirmwareVersion(3, 5, 0); vehicle->setFirmwareVersion(3, 5, 0);
break; break;
...@@ -774,6 +788,13 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -774,6 +788,13 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
} }
} }
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
if (majorVersion < 3) { if (majorVersion < 3) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
......
...@@ -195,6 +195,10 @@ void MissionCommandTreeTest::testAllTrees(void) ...@@ -195,6 +195,10 @@ void MissionCommandTreeTest::testAllTrees(void)
// This will cause all of the variants of collapsed trees to be built // This will cause all of the variants of collapsed trees to be built
foreach(MAV_AUTOPILOT firmwareType, firmwareList) { foreach(MAV_AUTOPILOT firmwareType, firmwareList) {
foreach (MAV_TYPE vehicleType, vehicleList) { foreach (MAV_TYPE vehicleType, vehicleList) {
if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_QUADROTOR) {
// VTOL in ArduPilot shows up as plane so we can test this pair
continue;
}
qDebug() << firmwareType << vehicleType; qDebug() << firmwareType << vehicleType;
Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager()); Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager());
QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL); QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment