From caa1de1563d2356d68f309b846c62fbd2f6eba58 Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Tue, 3 May 2016 20:17:00 -0700 Subject: [PATCH 1/4] Add ArduSub XML file and update firmware plugin to allow it to work --- qgcresources.qrc | 3 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 31 +- .../APM/APMParameterFactMetaData.Sub.3.4.xml | 5592 ++++++++++++++++++++ src/FirmwarePlugin/APM/APMParameterMetaData.cc | 24 +- 4 files changed, 5626 insertions(+), 24 deletions(-) create mode 100644 src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml diff --git a/qgcresources.qrc b/qgcresources.qrc index 3dba5b6..2bab644 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -175,7 +175,7 @@ resources/TrashDelete.svg resources/XDelete.svg resources/XDeleteBlack.svg - + resources/firmware/px4.png resources/firmware/apm.png @@ -266,6 +266,7 @@ src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml + src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index f4a0015..48c46f6 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -1,24 +1,24 @@ /*===================================================================== QGroundControl Open Source Ground Control Station - + (c) 2009 - 2015 QGROUNDCONTROL PROJECT - + This file is part of the QGROUNDCONTROL project - + QGROUNDCONTROL is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - + QGROUNDCONTROL is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - + You should have received a copy of the GNU General Public License along with QGROUNDCONTROL. If not, see . - + ======================================================================*/ /// @file @@ -37,18 +37,20 @@ static const QRegExp APM_COPTER_REXP("^(ArduCopter|APM:Copter)"); static const QRegExp APM_SOLO_REXP("^(APM:Copter solo-)"); static const QRegExp APM_PLANE_REXP("^(ArduPlane|APM:Plane)"); static const QRegExp APM_ROVER_REXP("^(ArduRover|APM:Rover)"); +static const QRegExp APM_SUB_REXP("^(ArduSub|APM:Sub)"); static const QRegExp APM_PX4NUTTX_REXP("^PX4: .*NuttX: .*"); static const QRegExp APM_FRAME_REXP("^Frame: "); static const QRegExp APM_SYSID_REXP("^PX4v2 "); // Regex to parse version text coming from APM, gives out firmware type, major, minor and patch level numbers -static const QRegExp VERSION_REXP("^(APM:Copter|APM:Plane|APM:Rover|ArduCopter|ArduPlane|ArduRover) +[vV](\\d*)\\.*(\\d*)*\\.*(\\d*)*"); +static const QRegExp VERSION_REXP("^(APM:Copter|APM:Plane|APM:Rover|APM:Sub|ArduCopter|ArduPlane|ArduRover|ArduSub) +[vV](\\d*)\\.*(\\d*)*\\.*(\\d*)*"); // minimum firmware versions that don't suffer from mavlink severity inversion bug. // https://github.com/diydrones/apm_planner/issues/788 static const QString MIN_SOLO_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Copter solo-1.2.0"); static const QString MIN_COPTER_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Copter V3.4.0"); static const QString MIN_PLANE_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Plane V3.4.0"); +static const QString MIN_SUB_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Sub V3.4.0"); static const QString MIN_ROVER_VERSION_WITH_CORRECT_SEVERITY_MSGS("APM:Rover V2.6.0"); const char* APMFirmwarePlugin::_artooIP = "10.1.1.1"; ///< IP address of ARTOO controller @@ -161,12 +163,12 @@ bool APMFirmwarePlugin::isCapable(FirmwareCapabilities capabilities) QList APMFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) { Q_UNUSED(vehicle); - + return QList(); } QStringList APMFirmwarePlugin::flightModes(void) -{ +{ QStringList flightModesList; foreach (const APMCustomMode& customMode, _supportedModes) { if (customMode.canBeSet()) { @@ -319,7 +321,7 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m if (!messageText.contains(APM_SOLO_REXP)) { // if don't know firmwareVersion yet, try and see if this message contains it - if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP)) { + if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP) || messageText.contains(APM_SUB_REXP)) { // found version string APMFirmwareVersion firmwareVersion(messageText); _textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(firmwareVersion); @@ -376,7 +378,7 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m // The following messages are incorrectly labeled as warning message. // Fixed in newer firmware (unreleased at this point), but still in older firmware. - if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP) || + if (messageText.contains(APM_COPTER_REXP) || messageText.contains(APM_PLANE_REXP) || messageText.contains(APM_ROVER_REXP) || messageText.contains(APM_SUB_REXP) || messageText.contains(APM_PX4NUTTX_REXP) || messageText.contains(APM_FRAME_REXP) || messageText.contains(APM_SYSID_REXP)) { _setInfoSeverity(message); } @@ -491,6 +493,10 @@ bool APMFirmwarePlugin::_isTextSeverityAdjustmentNeeded(const APMFirmwareVersion if (firmwareVersion < APMFirmwareVersion(MIN_ROVER_VERSION_WITH_CORRECT_SEVERITY_MSGS)) { adjustmentNeeded = true; } + } else if (firmwareVersion.vehicleType().contains(APM_SUB_REXP)) { + if (firmwareVersion < APMFirmwareVersion(MIN_SUB_VERSION_WITH_CORRECT_SEVERITY_MSGS)) { + adjustmentNeeded = true; + } } return adjustmentNeeded; @@ -654,8 +660,9 @@ QString APMFirmwarePlugin::getParameterMetaDataFile(Vehicle* vehicle) } case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_SURFACE_BOAT: - case MAV_TYPE_SUBMARINE: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); + case MAV_TYPE_SUBMARINE: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml"); default: return QString(); } diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml new file mode 100644 index 0000000..f43c693 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml @@ -0,0 +1,5592 @@ + + + + + + +-100 0 + + +True + + +True + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + + +Mission Planner and DroidPlanner + AP Planner 2 + + + + +Disabled +Enabled + + + +0 10 +.5 +Hz + + +0.0 1000.0 +10 +Centimeters + + +0.0 500.0 +10 + + + +None +FeedbackFromMid + + + +0 10 +1 +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 8000 +1 +Centimeters + + +0.5 10.0 + +Disabled +Shallow +Steep + +.1 + + +0 2000 +50 +cm/s + + +0.01 2.0 +0.01 + + + +Disabled +Land +RTL + + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode + + + +100 900 + + + +Disabled +Enabled + + + + +Disabled +Mode1 +Mode2 +Mode1+2 +Mode3 +Mode1+3 +Mode2+3 +Mode1+2+3 +Mode4 +Mode1+4 +Mode2+4 +Mode1+2+4 +Mode3+4 +Mode1+3+4 +Mode2+3+4 +Mode1+2+3+4 +Mode5 +Mode1+5 +Mode2+5 +Mode1+2+5 +Mode3+5 +Mode1+3+5 +Mode2+3+5 +Mode1+2+3+5 +Mode4+5 +Mode1+4+5 +Mode2+4+5 +Mode1+2+4+5 +Mode3+4+5 +Mode1+3+4+5 +Mode2+3+4+5 +Mode1+2+3+4+5 +Mode6 +Mode1+6 +Mode2+6 +Mode1+2+6 +Mode3+6 +Mode1+3+6 +Mode2+3+6 +Mode1+2+3+6 +Mode4+6 +Mode1+4+6 +Mode2+4+6 +Mode1+2+4+6 +Mode3+4+6 +Mode1+3+4+6 +Mode2+3+4+6 +Mode1+2+3+4+6 +Mode5+6 +Mode1+5+6 +Mode2+5+6 +Mode1+2+5+6 +Mode3+5+6 +Mode1+3+5+6 +Mode2+3+5+6 +Mode1+2+3+5+6 +Mode4+5+6 +Mode1+4+5+6 +Mode2+4+5+6 +Mode1+2+4+5+6 +Mode3+4+5+6 +Mode1+3+4+5+6 +Mode2+3+4+5+6 +Mode1+2+3+4+5+6 + + + +-1 1000 +1 +Centimeters + + +0 3000 +10 +Centimeters + + + +Never change yaw +Face next waypoint +Face next waypoint except RTL +Face along GPS course + + + +0 60000 +1000 +ms + + +30 200 +10 +cm/s + + +0 500 +10 +cm/s + + +50 500 +10 +Centimeters/Second + + +50 500 +10 +cm/s/s + + +0 300 +1 +Percent*10 + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always LAND + + + +925 1100 +1 +pwm + + +300 700 +10 +Percent*10 + + +0 300 +1 +pwm + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw + + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,16:WHEN_DISARMED,17:MOTBATT,18:IMU_FAST,19:IMU_RAW + +Default +Default+RCIN +Default+IMU +Default+Motors +NearlyAll-AC315 +NearlyAll +All+DisarmedLogging +All+FastATT +All+MotBatt +All+FastIMU +All+FastIMU+PID +All+FullIMU +Disabled + + + + +Normal Start-up +Start-up in ESC Calibration mode if throttle high +Start-up in ESC Calibration mode regardless of throttle +Disabled + + + + +None +Stab Roll/Pitch kP +Rate Roll/Pitch kP +Rate Roll/Pitch kI +Rate Roll/Pitch kD +Stab Yaw kP +Rate Yaw kP +Rate Yaw kD +Altitude Hold kP +Throttle Rate kP +Throttle Accel kP +Throttle Accel kI +Throttle Accel kD +Loiter Speed +Loiter Pos kP +Velocity XY kP +Velocity XY kI +WP Speed +Acro RollPitch kP +Acro Yaw kP +Heli Ext Gyro +OF Loiter kP +OF Loiter kI +OF Loiter kD +Declination +Circle Rate +RangeFinder Gain +Rate Pitch kP +Rate Pitch kI +Rate Pitch kD +Rate Roll kP +Rate Roll kI +Rate Roll kD +Rate Pitch FF +Rate Roll FF +Rate Yaw FF + + + +0 32767 + + +0 32767 + + + +Plus +X +V +H +V-Tail +A-Tail +Y6B (New) + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw + + + +0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Sonar,6:RC,7:Voltage + +Disabled +Enabled +Skip Baro +Skip Compass +Skip GPS +Skip INS +Skip Params/Sonar +Skip RC +Skip Voltage + + + +0 127 +Seconds + + +1000 8000 +Centi-degrees + + +0 100 + +Very Soft +Soft +Medium +Crisp +Very Crisp + +10 + + +4 12 +deg/sec + + +2000 4500 +Centi-degrees + + + +No repositioning +Repositioning + + + + +Land +AltHold +Land even in Stabilize + + + +0.6:Strict, 0.8:Default, 1.0:Relaxed + + + +Disabled +Enabled + + + +50 490 +1 +Hz + + +1 10 + + +1 10 + + +0 3 +0.1 + + +0 3 +0.1 + + + +Disabled +Leveling +Leveling and Limited + + + + +Disabled +Very Low +Low +Medium +High +Very High + + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0 4500 +10 +cm/s/s + + +Hz + + +1.000 8.000 + + +0.500 1.500 +0.05 + + +0.000 3.000 + + +0 1000 +Percent*10 + + +0.000 0.400 + + +1.000 100.000 +Hz + + +1.000 3.000 + + +0.500 2.000 + + +0.100 5.000 + + +0.100 5.000 + + +0 1000 +cm/s + + +0:Roll,1:Pitch,2:Yaw + +All +Roll Only +Pitch Only +Yaw Only +Roll and Pitch +Roll and Yaw +Pitch and Yaw + + + +0.05 0.10 + + +0.001 0.006 + + + +Stopped +Running + + + + +Do Not Use in RTL and Land 1 + + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + +Disabled +shift +arm_toggle +arm +disarm +mode_toggle +mode_stab +mode_althold +mount_center +mount_tilt_up +mount_tilt_down +camera_trigger +light1_cycle +lights1_brighter +lights1_dimmer +lights2_cycle +lights2_brighter +lights2_dimmer +gain_toggle +gain_inc +gain_dec +trim_roll_inc +trim_roll_dec +trim_pitch_inc +trim_pitch_dec + + + + + + +Servo +Relay + + + +0 50 +seconds + + +1000 2000 +pwm + + +1000 2000 +pwm + + +0 1000 +meters + + + +Low +High + + + +0 10000 +milliseconds + + +0 180 +Degrees + + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + + + + +TriggerLow +TriggerHigh + + + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Off +On +NoChange + + + + + + +Disabled +Enabled + + + +1000 2000 + + +1000 2000 + + +1000 2000 + + + +Never +every 15 seconds +every 30 seconds +once per minute + + + + + + +Disabled +Enabled + + + + +First Relay +Second Relay +Third Relay +Fourth Relay +Servo + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + +0 32000 +1 +Meters + + +0 5000 +1 +Milliseconds + + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-3.142 3.142 +0.01 +Radians + + + +Disabled +Internal-Learning +EKF-Learning + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +FirstCompass +SecondCompass +ThirdCompass + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + + + + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +4 20 +0.1 + + + + + +Unknown +APM1-1280 +APM1-2560 +APM2 +SITL +PX4v1 +PX4v2 +Flymaple +Linux + + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0 127 +Hz + + +0 127 +Hz + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0.05 50 + + + +Never +Start-up only + + + + +Don't adjust the trims +Assume first orientation was level +Assume ACC_BODYFIX is perfectly aligned to the vehicle + + + + +IMU 1 +IMU 2 +IMU 3 + + + + + +0 2000 +50 +cm/s + + +100 1000 +1 +cm + + +0 1000 +50 +cm/s + + +0 500 +10 +cm/s + + +0 2000 +50 +cm/s + + +50 500 +10 +cm/s/s + + +50 500 +10 +cm/s/s + + +500 5000 +1 +cm/s/s/s + + +100 981 +1 +cm/s/s + + +100 981 +1 +cm/s/s + + + + +0 10000 +100 +cm + + +-90 90 +1 +deg/s + + + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +500 18000 +100 +Centi-Degrees/Sec + + +0 72000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +3.000 12.000 + + +3.000 12.000 + + +3.000 6.000 + + + + +0.5 5 +0.1 +Hz + + + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + +0 10 +1 +Hz + + + + +0.0 1.0 +.01 + + + +Disabled +Enabled + + + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 + + + +0.001 0.5 +.01 + + +0 10 +1 + + + +Disabled +Enabled +Enable EKF2 + + + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0 100 +1 + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +SMBus +Bebop + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Watts + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +SMBus +Bebop + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Amps + + + + + +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture + + + + +Disabled +Enabled +Auto + + + + +Disabled +Enabled +Auto + + + + +Disabled +Enabled + + + + +Disabled +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz + + + +-32767 32768 + + + +Disabled +Enabled + + + + + + +Disabled +Enabled + + + +0 100 +percentage + + +1000 2000 +ms + + +0 1000 +cm/s + + +0 100 +percentage + + + + +True +True +1 +pascals + + +True +True +1 +degrees celsius + + +meters +0.1 + + + +FirstBaro +2ndBaro +3rdBaro + + + +1.0:Fresh Water, 1.024:Salt Water + + +pascals + + + +Keep +Reset + +True + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + + + + +Disabled +Enabled + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + + + +-100 90 +Degrees + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None +All +External only + + + + +Disabled +log every sample +log every 5 samples + +True + + +0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS + +Leave as currently configured +GPS-NoSBAS +GPS+SBAS +Galileo-NoSBAS +Galileo+SBAS +Beidou +GPS+IMES+QZSS+SBAS (Japan Only) +GLONASS +GLONASS+SBAS +GPS+GLONASS+SBAS + + + + +Do not save config +Save config +Save only when needed + + + +0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS + +Leave as currently configured +GPS-NoSBAS +GPS+SBAS +Galileo-NoSBAS +Galileo+SBAS +Beidou +GPS+IMES+QZSS+SBAS (Japan Only) +GLONASS +GLONASS+SBAS +GPS+GLONASS+SBAS + + + + +Disables automatic configuration +Enable automatic configuration + + + + + + +Disabled +ShowSlips +ShowOverruns + + + + +50Hz +100Hz +200Hz +250Hz +300Hz +400Hz + +True + + + + + +Disabled +Enabled + + + + +None +Altitude +Circle +Altitude and Circle + + + + +Report Only +RTL or Land + + + +10 1000 +1 +Meters + + +30 10000 +Meters + + +1 10 +Meters + + +10 1000 +1 +Meters + + + + + + +0.1 +kilometers + + + +DoNotIncludeHome +IncludeHome + + + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + + +normal +reverse + + + +0.0 1.5 +0.1 + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Disabled +Enabled + + + +0.05 5.0 +0.05 + + +0.05 5.0 +0.05 + + +0.1 10.0 +0.1 +meters + + +0.1 10.0 +0.1 +meters + + +0.01 0.5 +0.01 + + +0.5 5.0 +0.1 +m/s + + +0.01 1.0 +0.1 + + +0.0 1.0 +0.1 + + +0.001 0.05 +0.001 +rad/s + + +0.05 1.0 +0.01 +m/s/s + + +0.0000001 0.00001 +rad/s + + +0.00001 0.001 +m/s/s + + +0.0001 0.01 +gauss/s + + +0.0001 0.01 +gauss/s + + +0 500 +10 +milliseconds + + +0 500 +10 +milliseconds + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS use optical flow + + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + + +Speed and Height +Acceleration +Never +Always + + + +100 500 +50 + + +10 50 +5 +meters + + +1 50 +1 + + +0.05 1.0 +0.05 +rad/s + + +1 100 +1 + + +0 500 +10 +milliseconds + + +1 100 +1 + + +1.0 4.0 +0.1 + + + +Trust EKF more +Trust DCM more + + + + +Use Baro +Use Range Finder + + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + + + + +Disabled +Enabled + + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS use optical flow + + + +0.05 5.0 +0.05 +m/s + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + +0 250 +10 +msec + + + +Use Baro +Use Range Finder +Use GPS + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +msec + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s + + +0.05 1.0 +0.05 +rad/s + + +100 1000 +25 + + +0 250 +10 +msec + + +0.0001 0.01 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.0000001 0.00001 +rad/s + + +0.0000001 0.00001 +1/s + + +0.00001 0.001 +m/s/s + + +0.0001 0.01 +gauss/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +1 127 + + +50 200 +% + + +0.5 50.0 +m/s + + + + +0 32766 +1 + + + +Resume Mission +Restart Mission + + + + + + +Disabled +AnalogPin +RCChannelPwmValue + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixracer +Pixhawk ADC4 +Pixhawk ADC3 + Pixhawk ADC6 +Pixhawk SBUS + + + +0 5.0 +0.01 +Volt + + +0 5.0 +0.01 +Volt + + + + + +0 2000 +Microseconds + + +0 2000 +Microseconds + + + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 32767 +meters + + +0 127 +1 +centimeters + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +0 127 +1 + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +meters/Volt +0.001 + + +Volts +0.001 + + + +Linear +Inverted +Hyperbolic + + + +centimeters +1 + + +centimeters +1 + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +milliseconds +1 + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +meters/Volt +0.001 + + +Volts +0.001 + + + +Linear +Inverted +Hyperbolic + + + +centimeters +1 + + +centimeters +1 + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +milliseconds +1 + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + + + + +Disable +Enable + + + +meters +1 + + + + + +Disabled +Enabled + + + +-200 +200 +1 + + +-200 +200 +1 + + +-18000 +18000 +1 + + + + + +Disabled +Enabled Always Land +Enabled Strict + + + + +None +CompanionComputer +IRLock + + + +0 500 + + +0.100 5.000 + + +0.100 5.000 + + +0 1000 +cm/s + + + + + +None +PX4-PWM + + + +0.001 + + +1 + + +1 + + +0.1 + + + +None +PX4-PWM + + + +0.001 + + + + + +Disabled +Enabled + + + + +None +Loiter +LoiterAndDescend + + + + + + +Off +Low +Medium +High + + + + +Disable +Enable + + + + diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 27bc98b..9d204a2 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -1,24 +1,24 @@ /*===================================================================== - + QGroundControl Open Source Ground Control Station - + (c) 2009 - 2014 QGROUNDCONTROL PROJECT - + This file is part of the QGROUNDCONTROL project - + QGROUNDCONTROL is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. - + QGROUNDCONTROL is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. - + You should have received a copy of the GNU General Public License along with QGROUNDCONTROL. If not, see . - + ======================================================================*/ #include "APMParameterMetaData.h" @@ -69,9 +69,9 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, convertTo = QVariant::Double; break; } - + *convertOk = var.convert(convertTo); - + return var; } @@ -86,7 +86,6 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) case MAV_TYPE_QUADROTOR: case MAV_TYPE_COAXIAL: case MAV_TYPE_HELICOPTER: - case MAV_TYPE_SUBMARINE: case MAV_TYPE_HEXAROTOR: case MAV_TYPE_OCTOROTOR: case MAV_TYPE_TRICOPTER: @@ -104,6 +103,9 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) case MAV_TYPE_SURFACE_BOAT: vehicleName = "ArduRover"; break; + case MAV_TYPE_SUBMARINE: + vehicleName = "ArduSub"; + break; case MAV_TYPE_FLAPPING_WING: case MAV_TYPE_KITE: case MAV_TYPE_ONBOARD_CONTROLLER: @@ -129,7 +131,7 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData } _parameterMetaDataLoaded = true; - QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|AntennaTracker"); + QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|ArduSub|AntennaTracker"); QString currentCategory; qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << metaDataFile; From 9a61b951022677b0bc07cfa5c2265fffe997f0e8 Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Tue, 10 May 2016 13:46:06 -0700 Subject: [PATCH 2/4] Update ArduSub parameter XML file with recent additions. --- .../APM/APMParameterFactMetaData.Sub.3.4.xml | 320 ++++++++++++++++----- 1 file changed, 256 insertions(+), 64 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml index f43c693..880a914 100644 --- a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml @@ -1754,12 +1754,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1773,6 +1778,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1783,12 +1789,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1802,6 +1813,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1814,12 +1826,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1833,6 +1850,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1843,12 +1861,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1862,6 +1885,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1874,12 +1898,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1893,6 +1922,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1903,12 +1933,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1922,6 +1957,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1934,12 +1970,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1953,6 +1994,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1963,12 +2005,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -1982,6 +2029,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -1994,12 +2042,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2013,6 +2066,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2023,12 +2077,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2042,6 +2101,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2054,12 +2114,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2073,6 +2138,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2083,12 +2149,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2102,6 +2173,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2114,12 +2186,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2133,6 +2210,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2143,12 +2221,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2162,6 +2245,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2174,12 +2258,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2193,6 +2282,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2203,12 +2293,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2222,6 +2317,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2234,12 +2330,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2253,6 +2354,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2263,12 +2365,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2282,6 +2389,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2294,12 +2402,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2313,6 +2426,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2323,12 +2437,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2342,6 +2461,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2354,12 +2474,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2373,6 +2498,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2383,12 +2509,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2402,6 +2533,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2414,12 +2546,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2433,6 +2570,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2443,12 +2581,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2462,6 +2605,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2474,12 +2618,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2493,6 +2642,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2503,12 +2653,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2522,6 +2677,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2534,12 +2690,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2553,6 +2714,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2563,12 +2725,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2582,6 +2749,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2594,12 +2762,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2613,6 +2786,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2623,12 +2797,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2642,6 +2821,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2654,12 +2834,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2673,6 +2858,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle @@ -2683,12 +2869,17 @@ arm disarm mode_toggle -mode_stab -mode_althold +enter_mode_1 +enter_mode_2 +enter_mode_3 +enter_mode_4 +enter_mode_5 +enter_mode_6 mount_center mount_tilt_up mount_tilt_down camera_trigger +camera_source_toggle light1_cycle lights1_brighter lights1_dimmer @@ -2702,6 +2893,7 @@ trim_roll_dec trim_pitch_inc trim_pitch_dec +input_hold_toggle From 28e1ec6d5138af08a61ea0c374f18d15fe4722db Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Tue, 10 May 2016 15:52:26 -0700 Subject: [PATCH 3/4] Update ArduSub parameter XML file for typo. --- .../APM/APMParameterFactMetaData.Sub.3.4.xml | 64 +++++++++++----------- 1 file changed, 32 insertions(+), 32 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml index 880a914..4cfdc00 100644 --- a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml @@ -1765,7 +1765,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1800,7 +1800,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1837,7 +1837,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1872,7 +1872,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1909,7 +1909,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1944,7 +1944,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -1981,7 +1981,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2016,7 +2016,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2053,7 +2053,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2088,7 +2088,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2125,7 +2125,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2160,7 +2160,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2197,7 +2197,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2232,7 +2232,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2269,7 +2269,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2304,7 +2304,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2341,7 +2341,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2376,7 +2376,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2413,7 +2413,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2448,7 +2448,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2485,7 +2485,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2520,7 +2520,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2557,7 +2557,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2592,7 +2592,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2629,7 +2629,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2664,7 +2664,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2701,7 +2701,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2736,7 +2736,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2773,7 +2773,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2808,7 +2808,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2845,7 +2845,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle @@ -2880,7 +2880,7 @@ mount_tilt_down camera_trigger camera_source_toggle -light1_cycle +lights1_cycle lights1_brighter lights1_dimmer lights2_cycle From e524fda12454b64a9a1b2b7dd9f2af526b8844be Mon Sep 17 00:00:00 2001 From: Rustom Jehangir Date: Thu, 12 May 2016 11:09:51 -0700 Subject: [PATCH 4/4] Update ArduSub parameter file for new ArduPilot parameters. --- .../APM/APMParameterFactMetaData.Sub.3.4.xml | 284 +++++++++++++++++++-- 1 file changed, 269 insertions(+), 15 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml index 4cfdc00..dd3f193 100644 --- a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml @@ -383,7 +383,7 @@ -0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,16:WHEN_DISARMED,17:MOTBATT,18:IMU_FAST,19:IMU_RAW +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW Default Default+RCIN @@ -391,7 +391,6 @@ Default+Motors NearlyAll-AC315 NearlyAll -All+DisarmedLogging All+FastATT All+MotBatt All+FastIMU @@ -1193,6 +1192,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1254,6 +1277,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1315,6 +1362,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1376,6 +1447,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1437,6 +1532,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1498,6 +1617,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1559,6 +1702,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1620,6 +1787,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1681,6 +1872,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -1742,6 +1957,30 @@ EngineRunEnable HeliRSC HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 @@ -4396,6 +4635,18 @@ + + +Disabled +Enabled + + + + +Disabled +Enabled + + @@ -5239,6 +5490,14 @@ 0.5 50.0 m/s + + +Disabled +FirstIMU +FirstAndSecondIMU +AllIMUs + + @@ -5306,6 +5565,8 @@ BBB-PRU LightWareI2C LightWareSerial +Bebop +MAVLink @@ -5396,6 +5657,8 @@ BBB-PRU LightWareI2C LightWareSerial +Bebop +MAVLink @@ -5490,6 +5753,8 @@ BBB-PRU LightWareI2C LightWareSerial +Bebop +MAVLink @@ -5580,6 +5845,8 @@ BBB-PRU LightWareI2C LightWareSerial +Bebop +MAVLink @@ -5707,19 +5974,6 @@ IRLock - -0 500 - - -0.100 5.000 - - -0.100 5.000 - - -0 1000 -cm/s -