Browse Source

Hack to set vehicle type when FRAME_CLASS is not set.

QGC4.4
Don Gagne 4 years ago committed by Don Gagne
parent
commit
8aa3ec9c68
  1. 2
      src/AutoPilotPlugins/APM/APMAirframeComponent.qml
  2. 9
      src/Vehicle/MultiVehicleManager.cc

2
src/AutoPilotPlugins/APM/APMAirframeComponent.qml

@ -72,7 +72,7 @@ SetupPage { @@ -72,7 +72,7 @@ SetupPage {
qsTr("Currently set to frame class '%1'").arg(_frameClass.enumStringValue) +
(_frameTypeAvailable ? qsTr(" and frame type '%2'").arg(_frameType.enumStringValue) : "") +
qsTr(".", "period for end of sentence")) +
qsTr(" To change this configuration, select the desired frame class below.")
qsTr(" To change this configuration, select the desired frame class below and then reboot the vehicle.")
font.family: ScreenTools.demiboldFontFamily
wrapMode: Text.WordWrap
}

9
src/Vehicle/MultiVehicleManager.cc

@ -91,6 +91,15 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle @@ -91,6 +91,15 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
}
}
#if !defined(NO_ARDUPILOT_DIALECT)
// When you flash a new ArduCopter it does not set a FRAME_CLASS for some reason. This is the only ArduPilot variant which
// works this way. Because of this the vehicle type is not known at first connection. In order to make QGC work reasonably
// we assume ArduCopter for this case.
if (vehicleType == 0 && vehicleFirmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
vehicleType = MAV_TYPE_QUADROTOR;
}
#endif
if (_vehicles.count() > 0 && !qgcApp()->toolbox()->corePlugin()->options()->multiVehicleEnabled()) {
return;
}

Loading…
Cancel
Save