public void setAPType(byte sysid, byte compid)
{
MAVlist[sysid, compid].sysid = sysid;
MAVlist[sysid, compid].compid = compid;
switch (MAVlist[sysid, compid].apname)
{
case MAV_AUTOPILOT.ARDUPILOTMEGA:
switch (MAVlist[sysid, compid].aptype)
{
case MAVLink.MAV_TYPE.FIXED_WING:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduPlane;
break;
case MAVLink.MAV_TYPE.QUADROTOR:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.TRICOPTER:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.HEXAROTOR:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.OCTOROTOR:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.HELICOPTER:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduCopter2;
break;
case MAVLink.MAV_TYPE.GROUND_ROVER:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduRover;
break;
case MAV_TYPE.ANTENNA_TRACKER:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduTracker;
break;
default:
break;
}
break;
case MAV_AUTOPILOT.UDB:
switch (MAVlist[sysid, compid].aptype)
{
case MAVLink.MAV_TYPE.FIXED_WING:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.ArduPlane;
break;
}
break;
case MAV_AUTOPILOT.GENERIC:
switch (MAVlist[sysid, compid].aptype)
{
case MAVLink.MAV_TYPE.FIXED_WING:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.Ateryx;
break;
}
break;
case MAV_AUTOPILOT.PX4:
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.PX4;
break;
default:
switch (MAVlist[sysid, compid].aptype)
{
case MAV_TYPE.GIMBAL: // storm32 - name 83
MAVlist[sysid, compid].cs.firmware = MainV2.Firmwares.Gymbal;
break;
}
break;
}
}