|
|
|
@ -1809,12 +1809,12 @@ int Vehicle::motorCount()
@@ -1809,12 +1809,12 @@ int Vehicle::motorCount()
|
|
|
|
|
switch (_vehicleType) { |
|
|
|
|
case MAV_TYPE_HELICOPTER: |
|
|
|
|
return 1; |
|
|
|
|
case MAV_TYPE_VTOL_DUOROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: |
|
|
|
|
return 2; |
|
|
|
|
case MAV_TYPE_TRICOPTER: |
|
|
|
|
return 3; |
|
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_QUADROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: |
|
|
|
|
return 4; |
|
|
|
|
case MAV_TYPE_HEXAROTOR: |
|
|
|
|
return 6; |
|
|
|
@ -2431,11 +2431,11 @@ QString Vehicle::vehicleTypeName() const {
@@ -2431,11 +2431,11 @@ QString Vehicle::vehicleTypeName() const {
|
|
|
|
|
{ MAV_TYPE_FLAPPING_WING, tr("Flapping wing")}, |
|
|
|
|
{ MAV_TYPE_KITE, tr("Flapping wing")}, |
|
|
|
|
{ MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")}, |
|
|
|
|
{ MAV_TYPE_VTOL_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")}, |
|
|
|
|
{ MAV_TYPE_VTOL_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")}, |
|
|
|
|
{ MAV_TYPE_VTOL_TAILSITTER_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")}, |
|
|
|
|
{ MAV_TYPE_VTOL_TAILSITTER_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")}, |
|
|
|
|
{ MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")}, |
|
|
|
|
{ MAV_TYPE_VTOL_RESERVED2, tr("VTOL reserved 2")}, |
|
|
|
|
{ MAV_TYPE_VTOL_RESERVED3, tr("VTOL reserved 3")}, |
|
|
|
|
{ MAV_TYPE_VTOL_FIXEDROTOR, tr("VTOL Fixedrotor")}, |
|
|
|
|
{ MAV_TYPE_VTOL_TAILSITTER, tr("VTOL Tailsitter")}, |
|
|
|
|
{ MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")}, |
|
|
|
|
{ MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")}, |
|
|
|
|
{ MAV_TYPE_GIMBAL, tr("Onboard gimbal")}, |
|
|
|
|